From 0dcc1b6d101a1a47e15a0c6ef6f94d684ac56126 Mon Sep 17 00:00:00 2001 From: v0-e Date: Tue, 7 May 2024 16:39:32 +0100 Subject: [PATCH 01/22] rgen: init Co-authored-by: 6d7a --- utils/codegen/asn1ToConversionHeader-rgen.py | 90 ++ utils/codegen/asn1ToRosMsg-rgen.py | 90 ++ utils/codegen/docker/rgen.Dockerfile | 54 ++ utils/codegen/docker/rgen/.gitignore | 3 + utils/codegen/docker/rgen/Cargo.lock | 533 ++++++++++++ utils/codegen/docker/rgen/Cargo.toml | 21 + utils/codegen/docker/rgen/README.md | 11 + utils/codegen/docker/rgen/src/common/mod.rs | 60 ++ .../codegen/docker/rgen/src/conversion/bin.rs | 48 ++ .../docker/rgen/src/conversion/builder.rs | 589 +++++++++++++ .../codegen/docker/rgen/src/conversion/mod.rs | 73 ++ .../docker/rgen/src/conversion/template.rs | 645 +++++++++++++++ .../docker/rgen/src/conversion/utils.rs | 410 +++++++++ utils/codegen/docker/rgen/src/lib.rs | 3 + utils/codegen/docker/rgen/src/msgs/bin.rs | 46 ++ utils/codegen/docker/rgen/src/msgs/builder.rs | 709 ++++++++++++++++ utils/codegen/docker/rgen/src/msgs/mod.rs | 51 ++ .../codegen/docker/rgen/src/msgs/template.rs | 230 ++++++ utils/codegen/docker/rgen/src/msgs/utils.rs | 781 ++++++++++++++++++ utils/codegen/docker/rgen/tests/conversion.rs | 136 +++ utils/codegen/docker/rgen/tests/msgs.rs | 50 ++ utils/codegen/docker/rgen/tests/utils.rs | 61 ++ 22 files changed, 4694 insertions(+) create mode 100755 utils/codegen/asn1ToConversionHeader-rgen.py create mode 100755 utils/codegen/asn1ToRosMsg-rgen.py create mode 100644 utils/codegen/docker/rgen.Dockerfile create mode 100644 utils/codegen/docker/rgen/.gitignore create mode 100644 utils/codegen/docker/rgen/Cargo.lock create mode 100644 utils/codegen/docker/rgen/Cargo.toml create mode 100644 utils/codegen/docker/rgen/README.md create mode 100644 utils/codegen/docker/rgen/src/common/mod.rs create mode 100644 utils/codegen/docker/rgen/src/conversion/bin.rs create mode 100644 utils/codegen/docker/rgen/src/conversion/builder.rs create mode 100644 utils/codegen/docker/rgen/src/conversion/mod.rs create mode 100644 utils/codegen/docker/rgen/src/conversion/template.rs create mode 100644 utils/codegen/docker/rgen/src/conversion/utils.rs create mode 100644 utils/codegen/docker/rgen/src/lib.rs create mode 100644 utils/codegen/docker/rgen/src/msgs/bin.rs create mode 100644 utils/codegen/docker/rgen/src/msgs/builder.rs create mode 100644 utils/codegen/docker/rgen/src/msgs/mod.rs create mode 100644 utils/codegen/docker/rgen/src/msgs/template.rs create mode 100644 utils/codegen/docker/rgen/src/msgs/utils.rs create mode 100644 utils/codegen/docker/rgen/tests/conversion.rs create mode 100644 utils/codegen/docker/rgen/tests/msgs.rs create mode 100644 utils/codegen/docker/rgen/tests/utils.rs diff --git a/utils/codegen/asn1ToConversionHeader-rgen.py b/utils/codegen/asn1ToConversionHeader-rgen.py new file mode 100755 index 000000000..73654ed31 --- /dev/null +++ b/utils/codegen/asn1ToConversionHeader-rgen.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 + +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +import argparse +import glob +import os +import re +import shutil +import subprocess +import tempfile + +def parseCli(): + """Parses script's CLI arguments. + + Returns: + argparse.Namespace: arguments + """ + + parser = argparse.ArgumentParser( + description="Creates ROS .msg files from ASN1 definitions.", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument("files", type=str, nargs="+", help="ASN1 files") + parser.add_argument("-o", "--output-dir", type=str, required=True, help="output directory") + parser.add_argument("-td", "--temp-dir", type=str, default=None, help="temporary directory for mounting files to container; uses tempfile by default") + parser.add_argument("-m", "--message", type=str, required=True, help="message name") + parser.add_argument("-di", "--docker-image", type=str, default="ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen", help="rgen Docker image") + + args = parser.parse_args() + + return args + +def main(): + + args = parseCli() + + # create output directory + os.makedirs(args.output_dir, exist_ok=True) + + # create temporary directories for running asn1c in docker container + with tempfile.TemporaryDirectory() as temp_input_dir: + with tempfile.TemporaryDirectory() as temp_output_dir: + + if args.temp_dir is None: + container_input_dir = temp_input_dir + container_output_dir = temp_output_dir + else: + container_input_dir = os.path.join(args.temp_dir, "input") + container_output_dir = os.path.join(args.temp_dir, "output") + os.makedirs(container_input_dir, exist_ok=True) + os.makedirs(container_output_dir, exist_ok=True) + + # copy input asn1 files to temporary directory + for f in args.files: + shutil.copy(f, container_input_dir) + + # run asn1c docker container to generate header and source files + subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'conversion-headers', args.message], check=True) + + # move generated header and source files to output directories + for f in glob.glob(os.path.join(container_output_dir, "*.h")): + shutil.move(f, os.path.join(args.output_dir, os.path.basename(f))) + + +if __name__ == "__main__": + + main() diff --git a/utils/codegen/asn1ToRosMsg-rgen.py b/utils/codegen/asn1ToRosMsg-rgen.py new file mode 100755 index 000000000..14f19ea2b --- /dev/null +++ b/utils/codegen/asn1ToRosMsg-rgen.py @@ -0,0 +1,90 @@ +#!/usr/bin/env python3 + +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +import argparse +import glob +import os +import re +import shutil +import subprocess +import tempfile + +def parseCli(): + """Parses script's CLI arguments. + + Returns: + argparse.Namespace: arguments + """ + + parser = argparse.ArgumentParser( + description="Creates ROS .msg files from ASN1 definitions.", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument("files", type=str, nargs="+", help="ASN1 files") + parser.add_argument("-o", "--output-dir", type=str, required=True, help="output directory") + parser.add_argument("-td", "--temp-dir", type=str, default=None, help="temporary directory for mounting files to container; uses tempfile by default") + parser.add_argument("-m", "--message", type=str, required=True, help="message name") + parser.add_argument("-di", "--docker-image", type=str, default="ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen", help="rgen Docker image") + + args = parser.parse_args() + + return args + +def main(): + + args = parseCli() + + # create output directory + os.makedirs(args.output_dir, exist_ok=True) + + # create temporary directories for running asn1c in docker container + with tempfile.TemporaryDirectory() as temp_input_dir: + with tempfile.TemporaryDirectory() as temp_output_dir: + + if args.temp_dir is None: + container_input_dir = temp_input_dir + container_output_dir = temp_output_dir + else: + container_input_dir = os.path.join(args.temp_dir, "input") + container_output_dir = os.path.join(args.temp_dir, "output") + os.makedirs(container_input_dir, exist_ok=True) + os.makedirs(container_output_dir, exist_ok=True) + + # copy input asn1 files to temporary directory + for f in args.files: + shutil.copy(f, container_input_dir) + + # run asn1c docker container to generate header and source files + subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'msgs', args.message], check=True) + + # move generated header and source files to output directories + for f in glob.glob(os.path.join(container_output_dir, "*.msg")): + shutil.move(f, os.path.join(args.output_dir, os.path.basename(f))) + + +if __name__ == "__main__": + + main() diff --git a/utils/codegen/docker/rgen.Dockerfile b/utils/codegen/docker/rgen.Dockerfile new file mode 100644 index 000000000..04b62b48d --- /dev/null +++ b/utils/codegen/docker/rgen.Dockerfile @@ -0,0 +1,54 @@ +# docker build -t ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen -f rgen.Dockerfile . + +FROM ubuntu:22.04 + +# install essentials +RUN apt-get update && \ + apt-get install -y \ + build-essential \ + git \ + curl \ + tar \ + wget \ + && rm -rf /var/lib/apt/lists/* + +# install Rust/Cargo +ENV RUSTUP_HOME=/usr/local/rustup \ + CARGO_HOME=/usr/local/cargo \ + PATH=/usr/local/cargo/bin:$PATH +RUN curl --proto '=https' --tlsv1.2 -sSf https://sh.rustup.rs | sh -s -- -y + +# Compile .msg, conversion headers generators +WORKDIR /setup +COPY rgen/ rgen/ +WORKDIR /setup/rgen +RUN cargo build --release && \ + mv target/release/asn1-to-ros-msgs /usr/local/bin/asn1-to-ros-msgs && \ + mv target/release/asn1-to-ros-conversion-headers /usr/local/bin/asn1-to-ros-conversion-headers + +# cleanup +WORKDIR / +RUN rm -rf /setup + +# command +RUN mkdir input +RUN mkdir output +WORKDIR /output +RUN echo "\ +generator=\$1\n\ +pdu=\$2\n\ +case \$generator in\n\ + 'msgs')\n\ + asn1-to-ros-msgs -o . -p \$pdu \$(find /input -name '*.asn')\n\ + ;;\n\ + 'conversion-headers')\n\ + asn1-to-ros-conversion-headers -o . -p \$pdu \$(find /input -name '*.asn')\n\ + ;;\n\ + *)\n\ + echo 'Unknown generator \$generator'\n\ + exit 1\n\ + ;;\n\ +esac\n\ +" > /rgen.sh +ENTRYPOINT ["/bin/bash", "/rgen.sh"] +CMD ["msgs", "test"] diff --git a/utils/codegen/docker/rgen/.gitignore b/utils/codegen/docker/rgen/.gitignore new file mode 100644 index 000000000..1276b0ad1 --- /dev/null +++ b/utils/codegen/docker/rgen/.gitignore @@ -0,0 +1,3 @@ +/target +/out/* +!/out/.gitkeep diff --git a/utils/codegen/docker/rgen/Cargo.lock b/utils/codegen/docker/rgen/Cargo.lock new file mode 100644 index 000000000..c4e1db83e --- /dev/null +++ b/utils/codegen/docker/rgen/Cargo.lock @@ -0,0 +1,533 @@ +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 3 + +[[package]] +name = "aho-corasick" +version = "1.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8e60d3430d3a69478ad0993f19238d2df97c507009a52b3c10addcd7f6bcb916" +dependencies = [ + "memchr", +] + +[[package]] +name = "android-tzdata" +version = "0.1.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e999941b234f3131b00bc13c22d06e8c5ff726d1b6318ac7eb276997bbb4fef0" + +[[package]] +name = "android_system_properties" +version = "0.1.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "819e7219dbd41043ac279b19830f2efc897156490d7fd6ea916720117ee66311" +dependencies = [ + "libc", +] + +[[package]] +name = "anstream" +version = "0.6.13" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d96bd03f33fe50a863e394ee9718a706f988b9079b20c3784fb726e7678b62fb" +dependencies = [ + "anstyle", + "anstyle-parse", + "anstyle-query", + "anstyle-wincon", + "colorchoice", + "utf8parse", +] + +[[package]] +name = "anstyle" +version = "1.0.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8901269c6307e8d93993578286ac0edf7f195079ffff5ebdeea6a59ffb7e36bc" + +[[package]] +name = "anstyle-parse" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c75ac65da39e5fe5ab759307499ddad880d724eed2f6ce5b5e8a26f4f387928c" +dependencies = [ + "utf8parse", +] + +[[package]] +name = "anstyle-query" +version = "1.0.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e28923312444cdd728e4738b3f9c9cac739500909bb3d3c94b43551b16517648" +dependencies = [ + "windows-sys", +] + +[[package]] +name = "anstyle-wincon" +version = "3.0.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1cd54b81ec8d6180e24654d0b371ad22fc3dd083b6ff8ba325b72e00c87660a7" +dependencies = [ + "anstyle", + "windows-sys", +] + +[[package]] +name = "autocfg" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f1fdabc7756949593fe60f30ec81974b613357de856987752631dea1e3394c80" + +[[package]] +name = "bumpalo" +version = "3.15.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7ff69b9dd49fd426c69a0db9fc04dd934cdb6645ff000864d98f7e2af8830eaa" + +[[package]] +name = "cc" +version = "1.0.90" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8cd6604a82acf3039f1144f54b8eb34e91ffba622051189e71b781822d5ee1f5" + +[[package]] +name = "cfg-if" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" + +[[package]] +name = "chrono" +version = "0.4.37" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8a0d04d43504c61aa6c7531f1871dd0d418d91130162063b789da00fd7057a5e" +dependencies = [ + "android-tzdata", + "iana-time-zone", + "js-sys", + "num-traits", + "wasm-bindgen", + "windows-targets", +] + +[[package]] +name = "clap" +version = "4.5.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "90bc066a67923782aa8515dbaea16946c5bcc5addbd668bb80af688e53e548a0" +dependencies = [ + "clap_builder", + "clap_derive", +] + +[[package]] +name = "clap_builder" +version = "4.5.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ae129e2e766ae0ec03484e609954119f123cc1fe650337e155d03b022f24f7b4" +dependencies = [ + "anstream", + "anstyle", + "clap_lex", + "strsim", +] + +[[package]] +name = "clap_derive" +version = "4.5.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "528131438037fd55894f62d6e9f068b8f45ac57ffa77517819645d10aed04f64" +dependencies = [ + "heck", + "proc-macro2", + "quote", + "syn", +] + +[[package]] +name = "clap_lex" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "98cc8fbded0c607b7ba9dd60cd98df59af97e84d24e49c8557331cfc26d301ce" + +[[package]] +name = "colorchoice" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "acbf1af155f9b9ef647e42cdc158db4b64a1b61f743629225fde6f3e0be2a7c7" + +[[package]] +name = "core-foundation-sys" +version = "0.8.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "06ea2b9bc92be3c2baa9334a323ebca2d6f074ff852cd1d7b11064035cd3868f" + +[[package]] +name = "heck" +version = "0.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "2304e00983f87ffb38b55b444b5e3b60a884b5d30c0fca7d82fe33449bbe55ea" + +[[package]] +name = "iana-time-zone" +version = "0.1.60" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e7ffbb5a1b541ea2561f8c41c087286cc091e21e556a4f09a8f6cbf17b69b141" +dependencies = [ + "android_system_properties", + "core-foundation-sys", + "iana-time-zone-haiku", + "js-sys", + "wasm-bindgen", + "windows-core", +] + +[[package]] +name = "iana-time-zone-haiku" +version = "0.1.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f31827a206f56af32e590ba56d5d2d085f558508192593743f16b2306495269f" +dependencies = [ + "cc", +] + +[[package]] +name = "js-sys" +version = "0.3.69" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "29c15563dc2726973df627357ce0c9ddddbea194836909d655df6a75d2cf296d" +dependencies = [ + "wasm-bindgen", +] + +[[package]] +name = "libc" +version = "0.2.153" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9c198f91728a82281a64e1f4f9eeb25d82cb32a5de251c6bd1b5154d63a8e7bd" + +[[package]] +name = "log" +version = "0.4.21" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "90ed8c1e510134f979dbc4f070f87d4313098b704861a105fe34231c70a3901c" + +[[package]] +name = "memchr" +version = "2.7.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6c8640c5d730cb13ebd907d8d04b52f55ac9a2eec55b440c8892f40d56c76c1d" + +[[package]] +name = "minimal-lexical" +version = "0.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "68354c5c6bd36d73ff3feceb05efa59b6acb7626617f4962be322a825e61f79a" + +[[package]] +name = "nom" +version = "7.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d273983c5a657a70a3e8f2a01329822f3b8c8172b73826411a55751e404a0a4a" +dependencies = [ + "memchr", + "minimal-lexical", +] + +[[package]] +name = "num" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b05180d69e3da0e530ba2a1dae5110317e49e3b7f3d41be227dc5f92e49ee7af" +dependencies = [ + "num-complex", + "num-integer", + "num-iter", + "num-rational", + "num-traits", +] + +[[package]] +name = "num-complex" +version = "0.4.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "23c6602fda94a57c990fe0df199a035d83576b496aa29f4e634a8ac6004e68a6" +dependencies = [ + "num-traits", +] + +[[package]] +name = "num-integer" +version = "0.1.46" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7969661fd2958a5cb096e56c8e1ad0444ac2bbcd0061bd28660485a44879858f" +dependencies = [ + "num-traits", +] + +[[package]] +name = "num-iter" +version = "0.1.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d869c01cc0c455284163fd0092f1f93835385ccab5a98a0dcc497b2f8bf055a9" +dependencies = [ + "autocfg", + "num-integer", + "num-traits", +] + +[[package]] +name = "num-rational" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0638a1c9d0a3c0914158145bc76cff373a75a627e6ecbfb71cbe6f453a5a19b0" +dependencies = [ + "autocfg", + "num-integer", + "num-traits", +] + +[[package]] +name = "num-traits" +version = "0.2.18" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da0df0e5185db44f69b44f26786fe401b6c293d1907744beaa7fa62b2e5a517a" +dependencies = [ + "autocfg", +] + +[[package]] +name = "once_cell" +version = "1.19.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3fdb12b2476b595f9358c5161aa467c2438859caa136dec86c26fdd2efe17b92" + +[[package]] +name = "proc-macro2" +version = "1.0.79" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e835ff2298f5721608eb1a980ecaee1aef2c132bf95ecc026a11b7bf3c01c02e" +dependencies = [ + "unicode-ident", +] + +[[package]] +name = "quote" +version = "1.0.35" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "291ec9ab5efd934aaf503a6466c5d5251535d108ee747472c3977cc5acc868ef" +dependencies = [ + "proc-macro2", +] + +[[package]] +name = "rasn-compiler" +version = "0.1.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3adfed8c1b48b6b8bb4c889c947376c9d27c69557975de3a490111c6df32aff9" +dependencies = [ + "chrono", + "nom", + "num", + "proc-macro2", + "quote", + "wasm-bindgen", +] + +[[package]] +name = "regex" +version = "1.10.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c117dbdfde9c8308975b6a18d71f3f385c89461f7b3fb054288ecf2a2058ba4c" +dependencies = [ + "aho-corasick", + "memchr", + "regex-automata", + "regex-syntax", +] + +[[package]] +name = "regex-automata" +version = "0.4.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "86b83b8b9847f9bf95ef68afb0b8e6cdb80f498442f5179a29fad448fcc1eaea" +dependencies = [ + "aho-corasick", + "memchr", + "regex-syntax", +] + +[[package]] +name = "regex-syntax" +version = "0.8.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "adad44e29e4c806119491a7f06f03de4d1af22c3a680dd47f1e6e179439d1f56" + +[[package]] +name = "ros-backend" +version = "0.1.0" +dependencies = [ + "clap", + "rasn-compiler", + "regex", +] + +[[package]] +name = "strsim" +version = "0.11.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7da8b5736845d9f2fcb837ea5d9e2628564b3b043a70948a3f0b778838c5fb4f" + +[[package]] +name = "syn" +version = "2.0.58" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "44cfb93f38070beee36b3fef7d4f5a16f27751d94b187b666a5cc5e9b0d30687" +dependencies = [ + "proc-macro2", + "quote", + "unicode-ident", +] + +[[package]] +name = "unicode-ident" +version = "1.0.12" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3354b9ac3fae1ff6755cb6db53683adb661634f67557942dea4facebec0fee4b" + +[[package]] +name = "utf8parse" +version = "0.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "711b9620af191e0cdc7468a8d14e709c3dcdb115b36f838e601583af800a370a" + +[[package]] +name = "wasm-bindgen" +version = "0.2.92" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4be2531df63900aeb2bca0daaaddec08491ee64ceecbee5076636a3b026795a8" +dependencies = [ + "cfg-if", + "wasm-bindgen-macro", +] + +[[package]] +name = "wasm-bindgen-backend" +version = "0.2.92" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "614d787b966d3989fa7bb98a654e369c762374fd3213d212cfc0251257e747da" +dependencies = [ + "bumpalo", + "log", + "once_cell", + "proc-macro2", + "quote", + "syn", + "wasm-bindgen-shared", +] + +[[package]] +name = "wasm-bindgen-macro" +version = "0.2.92" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1f8823de937b71b9460c0c34e25f3da88250760bec0ebac694b49997550d726" +dependencies = [ + "quote", + "wasm-bindgen-macro-support", +] + +[[package]] +name = "wasm-bindgen-macro-support" +version = "0.2.92" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e94f17b526d0a461a191c78ea52bbce64071ed5c04c9ffe424dcb38f74171bb7" +dependencies = [ + "proc-macro2", + "quote", + "syn", + "wasm-bindgen-backend", + "wasm-bindgen-shared", +] + +[[package]] +name = "wasm-bindgen-shared" +version = "0.2.92" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "af190c94f2773fdb3729c55b007a722abb5384da03bc0986df4c289bf5567e96" + +[[package]] +name = "windows-core" +version = "0.52.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "33ab640c8d7e35bf8ba19b884ba838ceb4fba93a4e8c65a9059d08afcfc683d9" +dependencies = [ + "windows-targets", +] + +[[package]] +name = "windows-sys" +version = "0.52.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "282be5f36a8ce781fad8c8ae18fa3f9beff57ec1b52cb3de0789201425d9a33d" +dependencies = [ + "windows-targets", +] + +[[package]] +name = "windows-targets" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7dd37b7e5ab9018759f893a1952c9420d060016fc19a472b4bb20d1bdd694d1b" +dependencies = [ + "windows_aarch64_gnullvm", + "windows_aarch64_msvc", + "windows_i686_gnu", + "windows_i686_msvc", + "windows_x86_64_gnu", + "windows_x86_64_gnullvm", + "windows_x86_64_msvc", +] + +[[package]] +name = "windows_aarch64_gnullvm" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bcf46cf4c365c6f2d1cc93ce535f2c8b244591df96ceee75d8e83deb70a9cac9" + +[[package]] +name = "windows_aarch64_msvc" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da9f259dd3bcf6990b55bffd094c4f7235817ba4ceebde8e6d11cd0c5633b675" + +[[package]] +name = "windows_i686_gnu" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b474d8268f99e0995f25b9f095bc7434632601028cf86590aea5c8a5cb7801d3" + +[[package]] +name = "windows_i686_msvc" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1515e9a29e5bed743cb4415a9ecf5dfca648ce85ee42e15873c3cd8610ff8e02" + +[[package]] +name = "windows_x86_64_gnu" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5eee091590e89cc02ad514ffe3ead9eb6b660aedca2183455434b93546371a03" + +[[package]] +name = "windows_x86_64_gnullvm" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "77ca79f2451b49fa9e2af39f0747fe999fcda4f5e241b2898624dca97a1f2177" + +[[package]] +name = "windows_x86_64_msvc" +version = "0.52.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "32b752e52a2da0ddfbdbcc6fceadfeede4c939ed16d13e648833a61dfb611ed8" diff --git a/utils/codegen/docker/rgen/Cargo.toml b/utils/codegen/docker/rgen/Cargo.toml new file mode 100644 index 000000000..b9e27e986 --- /dev/null +++ b/utils/codegen/docker/rgen/Cargo.toml @@ -0,0 +1,21 @@ +[package] +name = "ros-backend" +version = "0.1.0" +edition = "2021" + +[lib] +name = "ros_backend" +path = "src/lib.rs" + +[[bin]] +name = "asn1-to-ros-msgs" +path = "src/msgs/bin.rs" + +[[bin]] +name = "asn1-to-ros-conversion-headers" +path = "src/conversion/bin.rs" + +[dependencies] +rasn-compiler = "0.1.4" +regex = "1.10.4" +clap = { version = "4.5.4", features = ["derive"] } diff --git a/utils/codegen/docker/rgen/README.md b/utils/codegen/docker/rgen/README.md new file mode 100644 index 000000000..71c7fea6d --- /dev/null +++ b/utils/codegen/docker/rgen/README.md @@ -0,0 +1,11 @@ +# ASN.1 to ROS Compiler +Backends for the rasn compiler, which converts ASN.1 files to ROS message files, and generates support conversion headers for translation between asn1c structs and ROS structs. + +Support mainly for ETSI ITS messages. + +## Usage +To generate the ROS `.msg`s run `cargo run --bin asn1-to-ros-msgs -- -p -o [ASN.1 files ...]`, where `` is the main PDU name used as a reference (e.g. `cam`, `denm`), and `` is the output directory. + +To generate the conversion headers run `cargo run --bin asn1-to-ros-conversion-headers -- -p -o [ASN.1 files ...]`. + +The corresponding ROS `.msg`s and conversion headers will be generated in the `out` directory. diff --git a/utils/codegen/docker/rgen/src/common/mod.rs b/utils/codegen/docker/rgen/src/common/mod.rs new file mode 100644 index 000000000..5218c1440 --- /dev/null +++ b/utils/codegen/docker/rgen/src/common/mod.rs @@ -0,0 +1,60 @@ +use rasn_compiler::prelude::ir::IntegerType; + +pub trait IntegerTypeExt { + fn to_str(self) -> &'static str; +} + +impl IntegerTypeExt for IntegerType { + fn to_str(self) -> &'static str { + match self { + IntegerType::Int8 => "int8", + IntegerType::Uint8 => "uint8", + IntegerType::Int16 => "int16", + IntegerType::Uint16 => "uint16", + IntegerType::Int32 => "int32", + IntegerType::Uint32 => "uint32", + IntegerType::Int64 => "int64", + IntegerType::Uint64 => "uint64", + IntegerType::Unbounded => "int64", + } + } +} +pub fn to_ros_snake_case(input: &str) -> String { + let input = input.replace('-', "_"); + let mut lowercase = String::with_capacity(input.len()); + + let peekable = &mut input.chars().peekable(); + while let Some(c) = peekable.next() { + if c.is_lowercase() || c.is_numeric() { + lowercase.push(c); + /* underscore before uppercase following a lowercase, aBx -> a_bx */ + if c != '_' && peekable.peek().map_or(false, |next| next.is_uppercase()) { + lowercase.push('_'); + } + } else { + /* underscore before uppercase followed by lowercase, ABx -> a_bx */ + if c != '_' + && lowercase.len() > 0 + && !lowercase.ends_with('_') + && peekable.peek().map_or(false, |next| next.is_lowercase()) + { + lowercase.push('_'); + } + lowercase.push(c.to_ascii_lowercase()); + } + } + lowercase +} + +pub fn to_ros_const_case(input: &str) -> String { + to_ros_snake_case(input).to_string().to_uppercase() +} + +pub fn to_ros_title_case(input: &str) -> String { + if !input.is_empty() { + let input = input.replace('-', ""); + input[0..1].to_uppercase() + &input[1..] + } else { + input.to_string() + } +} diff --git a/utils/codegen/docker/rgen/src/conversion/bin.rs b/utils/codegen/docker/rgen/src/conversion/bin.rs new file mode 100644 index 000000000..26aca9af6 --- /dev/null +++ b/utils/codegen/docker/rgen/src/conversion/bin.rs @@ -0,0 +1,48 @@ +use std::path::PathBuf; + +use clap::Parser; +use regex::Regex; + +use rasn_compiler::prelude::*; +use ros_backend::conversion::Conversion; + +#[derive(Parser, Debug)] +struct Cli { + /// Main PDU name + #[arg(short, long)] + pdu: String, + #[clap(short, long)] + /// Output directory + out: std::path::PathBuf, + /// ASN.1 files to compile + paths: Vec, +} + +fn main() { + let args = Cli::parse(); + + let backend = Conversion::default().set_main_pdu_name(&args.pdu.clone()); + + // Compile conversion headers + let compiler_res = Compiler::new() + .with_backend(backend) + .add_asn_sources_by_path(args.paths.iter()) + .compile_to_string(); + let generated = &compiler_res.unwrap().generated; + + // Split generated code into individual messages + let re_name = Regex::new(r"\/\/\/\/\s([\w-]+)\s(\w+)\b").unwrap(); + let re_def = Regex::new(r"#\n((.|\n)*?)#").unwrap(); + generated.split_inclusive("").for_each(|s| { + if let Some(def_caps) = re_def.captures(s) { + let definition = def_caps.get(1).unwrap().as_str(); + let name = if let Some(name_caps) = re_name.captures(definition) { + name_caps.get(2).unwrap().as_str() + } else { + "unknown" + }; + let path = args.out.join(format!("convert{}.h", name)); + std::fs::write(path, definition).unwrap(); + } + }); +} diff --git a/utils/codegen/docker/rgen/src/conversion/builder.rs b/utils/codegen/docker/rgen/src/conversion/builder.rs new file mode 100644 index 000000000..d0c5ffa50 --- /dev/null +++ b/utils/codegen/docker/rgen/src/conversion/builder.rs @@ -0,0 +1,589 @@ +use std::error::Error; + +use rasn_compiler::prelude::{ir::*, *}; + +use crate::common::{to_ros_const_case, to_ros_title_case, IntegerTypeExt}; +use crate::conversion::{generate, Conversion, ConversionOptions}; +use crate::conversion::{template::*, utils::*}; + +pub(crate) const INNER_ARRAY_LIKE_PREFIX: &str = "Anonymous_"; + +impl Backend for Conversion { + fn generate_module( + &self, + tlds: Vec, + ) -> Result { + let tlds = merge_tlds(tlds); + let (pdus, warnings): (Vec, Vec>) = + tlds.into_iter().fold((vec![], vec![]), |mut acc, tld| { + match generate(&self.options, tld) { + Ok(s) => { + s.len().gt(&0).then(|| { + acc.0.push(format!( + "#\n\ + {s}\n\ + #" + )) + }); + acc + } + Err(e) => { + acc.1.push(Box::new(e)); + acc + } + } + }); + Ok(GeneratedModule { + generated: Some(format!("{}", pdus.join("\n\n"))), + warnings, + }) + } +} + +pub fn merge_tlds(tlds: Vec) -> Vec { + let mut merged_tlds = Vec::::with_capacity(tlds.len()); + let mut merge_to = Vec::<(&ToplevelDefinition, &String)>::new(); + + // Add value to type's distinguished values + tlds.iter().for_each(|tld| { + if let ToplevelDefinition::Value(v) = &tld { + if let ASN1Value::LinkedIntValue { .. } = &v.value { + merge_to.push((&tld, &v.associated_type)); + } else { + merged_tlds.push(tld.clone()); + } + } else { + merged_tlds.push(tld.clone()); + } + }); + merge_to.iter().for_each(|(tld, ty)| { + for t in &mut merged_tlds { + if let ToplevelDefinition::Type(tt) = t { + if tt.name == **ty { + if let ASN1Type::Integer(ref mut int) = tt.ty { + let value = match &tld { + ToplevelDefinition::Value(v) => { + if let ASN1Value::LinkedIntValue { + integer_type: _, + value, + } = &v.value + { + value + } else { + unreachable!() + } + } + _ => unreachable!(), + }; + match int.distinguished_values { + Some(ref mut dv) => dv.push(DistinguishedValue { + name: tld.name().clone(), + value: *value, + }), + None => { + int.distinguished_values = Some(vec![DistinguishedValue { + name: tld.name().clone(), + value: *value, + }]); + } + } + } + break; + } + } + } + }); + + // Resolve object set references + let mut object_sets = Vec::<(String, ObjectSet)>::new(); + merged_tlds.iter().for_each(|tld| { + if let ToplevelDefinition::Information(i) = tld { + if let ASN1Information::ObjectSet(os) = &i.value { + object_sets.push((tld.name().clone(), os.clone())); + } + } + }); + merged_tlds.iter_mut().for_each(|tld| { + if let ToplevelDefinition::Type(t) = tld { + if let ASN1Type::Sequence(ref mut s) = t.ty { + s.members.iter_mut().for_each(|m| { + if let ASN1Type::InformationObjectFieldReference(ref mut r) = m.ty { + if let Constraint::TableConstraint(ref mut c) = r.constraints[0] { + if let ObjectSetValue::Reference(ref mut osvr) = c.object_set.values[0] + { + object_sets + .iter() + .find(|s| s.0 == *osvr) + .and_then(|(_, os)| { + let mut os = os.clone(); + os.values.push(c.object_set.values[0].clone()); + c.object_set = os; + Some(()) + }); + } + } + } + }); + } + } + }); + merged_tlds +} + +pub fn generate_typealias( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::ElsewhereDeclaredType(dec) = &tld.ty { + Ok(typealias_template( + &options, + &format_comments(&tld.comments)?, + &tld.name, + &dec.identifier, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected type alias top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_integer_value(tld: ToplevelValueDefinition) -> Result { + if let ASN1Value::LinkedIntValue { integer_type, .. } = tld.value { + let formatted_value = value_to_tokens(&tld.value, None)?; + let formatted_name = to_ros_const_case(&tld.name); + let ty = integer_type.to_str(); + if tld.associated_type == INTEGER { + Ok(lazy_static_value_template( + &format_comments(&tld.comments)?, + &formatted_name, + "int64", + &formatted_value, + )) + } else if integer_type.is_unbounded() { + Ok(lazy_static_value_template( + &format_comments(&tld.comments)?, + &formatted_name, + ty, + &formatted_value, + )) + } else { + Ok(integer_value_template( + &format_comments(&tld.comments)?, + &formatted_name, + ty, + &formatted_value, + )) + } + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Value(tld)), + "Expected INTEGER value top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_integer( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::Integer(_) = tld.ty { + Ok(integer_template( + &options, + &format_comments(&tld.comments)?, + &to_ros_title_case(&tld.name), + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected INTEGER top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_bit_string( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::BitString(_) = tld.ty { + Ok(bit_string_template( + &options, + &format_comments(&tld.comments)?, + &tld.name, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected BIT STRING top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_octet_string( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::OctetString(ref _oct_str) = tld.ty { + Ok(octet_string_template( + &options, + &format_comments(&tld.comments)?, + &tld.name, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected OCTET STRING top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_character_string( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::CharacterString(ref char_str) = tld.ty { + Ok(char_string_template( + &options, + &format_comments(&tld.comments)?, + &tld.name, + &string_type(&char_str.ty)?, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected Character String top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_boolean( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::Boolean(_) = tld.ty { + Ok(boolean_template( + options, + &format_comments(&tld.comments)?, + &tld.name, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected BOOLEAN top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +macro_rules! call_template { + ($fn:ident, $tld:ident, $($args:expr),*) => { + Ok($fn( + &format_comments(&$tld.comments)?, + (&$tld.name), + $($args),* + )) + }; +} + +macro_rules! assignment { + ($unformatted:expr, $inner:expr) => {{ + let _ty = ($unformatted); + let _inner = $inner; + "quote!(#ty(#inner))".into() + }}; +} + +pub fn generate_value(tld: ToplevelValueDefinition) -> Result { + let ty = tld.associated_type.as_str(); + match &tld.value { + ASN1Value::Null if ty == NULL => { + call_template!( + primitive_value_template, + tld, + "quote!(())".into(), + "quote!(())".into() + ) + } + ASN1Value::Null => call_template!( + primitive_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, "byte null 0".to_string()) + ), + ASN1Value::Boolean(b) if ty == BOOLEAN => { + call_template!(primitive_value_template, tld, "bool", &b.to_string()) + } + ASN1Value::Boolean(b) => call_template!( + primitive_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, b.to_string()) + ), + ASN1Value::LinkedIntValue { .. } => generate_integer_value(tld), + ASN1Value::BitString(_) if ty == BIT_STRING => todo!(), + ASN1Value::OctetString(_) if ty == OCTET_STRING => todo!(), + ASN1Value::Choice { + variant_name, + inner_value, + .. + } => { + if inner_value.is_const_type() { + call_template!( + const_choice_value_template, + tld, + &tld.associated_type, + variant_name, + &value_to_tokens(inner_value, None)? + ) + } else { + call_template!( + choice_value_template, + tld, + &tld.associated_type, + &variant_name, + &value_to_tokens(inner_value, None)? + ) + } + } + ASN1Value::EnumeratedValue { + enumerated, + enumerable, + } => call_template!(enum_value_template, tld, enumerated, enumerable), + ASN1Value::Time(_) if ty == GENERALIZED_TIME => todo!(), + ASN1Value::Time(_) if ty == UTC_TIME => todo!(), + ASN1Value::LinkedStructLikeValue(s) => { + let _members = s + .iter() + .map(|(_, _, val)| value_to_tokens(val.value(), None)) + .collect::, _>>()?; + todo!() + } + ASN1Value::LinkedNestedValue { supertypes, value } => { + let parent = supertypes.last().map(|s| (s)); + if value.is_const_type() { + call_template!( + primitive_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) + ) + } else { + call_template!( + lazy_static_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) + ) + } + } + ASN1Value::ObjectIdentifier(_) if ty == OBJECT_IDENTIFIER => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == NUMERIC_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == VISIBLE_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == IA5_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == UTF8_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == BMP_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == PRINTABLE_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == GENERAL_STRING => todo!(), + ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SEQUENCE_OF) => { + let _item_type = format_sequence_or_set_of_item_type( + ty.replace(SEQUENCE_OF, "").trim().to_string(), + s.first().map(|i| &**i), + ); + todo!() + } + ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SET_OF) => { + let _item_type = format_sequence_or_set_of_item_type( + ty.replace(SET_OF, "").trim().to_string(), + s.first().map(|i| &**i), + ); + todo!() + } + ASN1Value::BitString(_) + | ASN1Value::Time(_) + | ASN1Value::LinkedCharStringValue(_, _) + | ASN1Value::ObjectIdentifier(_) + | ASN1Value::LinkedArrayLikeValue(_) + | ASN1Value::ElsewhereDeclaredValue { .. } + | ASN1Value::OctetString(_) => call_template!( + lazy_static_value_template, + tld, + &tld.associated_type.to_string(), + assignment!(&tld.associated_type, value_to_tokens(&tld.value, None)?) + ), + _ => Ok("".to_string()), + } +} + +pub fn generate_any(tld: ToplevelTypeDefinition) -> Result { + Ok(any_template(&format_comments(&tld.comments)?, &tld.name)) +} + +pub fn generate_generalized_time(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::GeneralizedTime(_) = &tld.ty { + Ok(generalized_time_template( + &format_comments(&tld.comments)?, + &tld.name, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected GeneralizedTime top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_utc_time(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::UTCTime(_) = &tld.ty { + Ok(utc_time_template( + &format_comments(&tld.comments)?, + &tld.name, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected UTCTime top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_oid(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::ObjectIdentifier(_oid) = &tld.ty { + Ok(oid_template(&format_comments(&tld.comments)?, &tld.name)) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected OBJECT IDENTIFIER top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_null(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::Null = tld.ty { + Ok(null_template(&format_comments(&tld.comments)?, &tld.name)) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected NULL top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_enumerated( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::Enumerated(_) = tld.ty { + Ok(enumerated_template( + &options, + &format_comments(&tld.comments)?, + &tld.name, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected ENUMERATED top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_choice( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + if let ASN1Type::Choice(ref choice) = tld.ty { + let members = get_choice_members_names(choice); + Ok(choice_template( + &options, + &format_comments(&tld.comments)?, + &tld.name, + &members, + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected CHOICE top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_sequence_or_set( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + match tld.ty { + ASN1Type::Sequence(ref seq) | ASN1Type::Set(ref seq) => { + let members = get_sequence_or_set_members_names(seq); + Ok(sequence_or_set_template( + options, + &format_comments(&tld.comments)?, + &tld.name, + members, + )) + } + _ => Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected SEQUENCE top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )), + } +} + +pub fn generate_sequence_or_set_of( + options: &ConversionOptions, + tld: ToplevelTypeDefinition, +) -> Result { + let (is_set_of, seq_or_set_of) = match &tld.ty { + ASN1Type::SetOf(se_of) => (true, se_of), + ASN1Type::SequenceOf(se_of) => (false, se_of), + _ => { + return Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected SEQUENCE OF top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } + }; + let anonymous_item = match seq_or_set_of.element_type.as_ref() { + ASN1Type::ElsewhereDeclaredType(_) => None, + n => Some(generate( + &ConversionOptions::default(), + ToplevelDefinition::Type(ToplevelTypeDefinition { + parameterization: None, + comments: format!( + " Anonymous {} OF member ", + if is_set_of { "SET" } else { "SEQUENCE" } + ), + name: String::from(INNER_ARRAY_LIKE_PREFIX) + &tld.name, + ty: n.clone(), + tag: None, + index: None, + }), + )?), + } + .unwrap_or_default(); + let member_type = match seq_or_set_of.element_type.as_ref() { + ASN1Type::ElsewhereDeclaredType(d) => d.identifier.clone(), + _ => format!("Anonymous{}", &tld.name), + }; + Ok(sequence_or_set_of_template( + &options, + is_set_of, + &format_comments(&tld.comments)?, + &tld.name, + &anonymous_item, + &member_type, + )) +} diff --git a/utils/codegen/docker/rgen/src/conversion/mod.rs b/utils/codegen/docker/rgen/src/conversion/mod.rs new file mode 100644 index 000000000..5a42fb498 --- /dev/null +++ b/utils/codegen/docker/rgen/src/conversion/mod.rs @@ -0,0 +1,73 @@ +use rasn_compiler::prelude::{ir::ASN1Type, *}; + +mod builder; +mod template; +mod utils; + +#[derive(Default)] +pub struct Conversion { + options: ConversionOptions, +} +pub struct ConversionOptions { + main_pdu: String, +} +impl Default for ConversionOptions { + fn default() -> Self { + Self { + main_pdu: "pdu".into(), + } + } +} +impl Conversion { + pub fn set_main_pdu_name(mut self, main_pdu_name: &str) -> Self { + self.options.main_pdu = main_pdu_name.to_owned(); + self + } +} + +use builder::*; + +fn generate( + options: &ConversionOptions, + tld: ToplevelDefinition, +) -> Result { + match tld { + ToplevelDefinition::Type(t) => { + if t.parameterization.is_some() { + return Ok("".into()); + } + match t.ty { + ASN1Type::Null => generate_null(t), + ASN1Type::Boolean(_) => generate_boolean(&options, t), + ASN1Type::Integer(_) => generate_integer(&options, t), + ASN1Type::Enumerated(_) => generate_enumerated(&options, t), + ASN1Type::BitString(_) => generate_bit_string(&options, t), + ASN1Type::CharacterString(_) => generate_character_string(&options, t), + ASN1Type::Sequence(_) | ASN1Type::Set(_) => generate_sequence_or_set(&options, t), + ASN1Type::SequenceOf(_) | ASN1Type::SetOf(_) => { + generate_sequence_or_set_of(&options, t) + } + ASN1Type::ElsewhereDeclaredType(_) => generate_typealias(&options, t), + ASN1Type::Choice(_) => generate_choice(&options, t), + ASN1Type::OctetString(_) => generate_octet_string(&options, t), + ASN1Type::Time(_) => unimplemented!("rasn does not support TIME types yet!"), + ASN1Type::Real(_) => Err(GeneratorError { + kind: GeneratorErrorType::NotYetInplemented, + details: "Real types are currently unsupported!".into(), + top_level_declaration: None, + }), + ASN1Type::ObjectIdentifier(_) => generate_oid(t), + ASN1Type::InformationObjectFieldReference(_) + | ASN1Type::EmbeddedPdv + | ASN1Type::External => generate_any(t), + ASN1Type::GeneralizedTime(_) => generate_generalized_time(t), + ASN1Type::UTCTime(_) => generate_utc_time(t), + ASN1Type::ChoiceSelectionType(_) => unreachable!(), + } + } + ToplevelDefinition::Value(v) => generate_value(v), + ToplevelDefinition::Information(i) => match i.value { + _ => Ok("".into()), + }, + } +} diff --git a/utils/codegen/docker/rgen/src/conversion/template.rs b/utils/codegen/docker/rgen/src/conversion/template.rs new file mode 100644 index 000000000..312d9e6ce --- /dev/null +++ b/utils/codegen/docker/rgen/src/conversion/template.rs @@ -0,0 +1,645 @@ +use crate::common::{to_ros_const_case, to_ros_snake_case, to_ros_title_case}; +use crate::conversion::utils::{InnerTypes, NameType, NamedSeqMember}; +use crate::conversion::ConversionOptions; + +use std::collections::HashMap; + +const CONVERSION_TEMPLATE: &str = r#"//// {asn1_type} {name} +{comments} + +#pragma once + +#include + +#include +{c_includes} +#ifdef ROS1 +{ros1_includes} +namespace {pdu}_msgs = etsi_its_{pdu}_msgs; +#else +{ros2_includes} +namespace {pdu}_msgs = etsi_its_{pdu}_msgs::msg; +#endif + + +namespace etsi_its_{pdu}_conversion { + +void toRos_{type}(const {c_type}_t& in, {pdu}_msgs::{ros_type}& out) { + {to_ros_members} +} + +void toStruct_{type}(const {pdu}_msgs::{ros_type}& in, {c_type}_t& out) { + memset(&out, 0, sizeof({c_type}_t)); + + {to_c_members} +} + +}"#; + +pub fn conversion_template( + comments: &str, + pdu: &str, + includes: &Vec, + name: &str, + asn1_type: &str, + to_ros_members: &str, + to_c_members: &str, +) -> String { + let c_includes = includes + .iter() + .map(|member| { + if !member.is_primitive { + format!( + "#include ", + pdu = pdu, + dep = member.ty + ) + } else { + format!( + "#include ", + pdu = pdu, + dep = member.ty + ) + "\n" + + &format!( + "#include ", + dep = member.ty + ) + } + }) + .collect::>() + .join("\n"); + let ros1_includes = format!( + "#include ", + pdu = pdu, + ros_fn = to_ros_title_case(name) + ); + let ros2_includes = format!( + "#include ", + pdu = pdu, + ros_fn = to_ros_snake_case(name) + ); + + CONVERSION_TEMPLATE + .replace("{comments}", comments) + .replace("{c_includes}", &c_includes) + .replace("{ros1_includes}", &ros1_includes) + .replace("{ros2_includes}", &ros2_includes) + .replace("{asn1_type}", asn1_type) + .replace("{name}", name) + .replace("{c_type}", name) + .replace("{type}", name) + .replace("{ros_type}", &to_ros_title_case(name)) + .replace("{pdu}", pdu) + .replace("{to_ros_members}", &to_ros_members) + .replace("{to_c_members}", &to_c_members) +} + +pub fn typealias_template( + options: &ConversionOptions, + comments: &str, + name: &str, + alias: &str, +) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![NameType { + name: name.to_string(), + ty: alias.to_string(), + is_primitive: false, + inner_types: None, + }], + name, + "TYPEALIAS", + &format!("toRos_{alias}(in, out.value);"), + &format!("toStruct_{alias}(in.value, out);"), + ) +} + +pub fn integer_value_template(_comments: &str, _name: &str, _vtype: &str, _value: &str) -> String { + todo!() +} + +pub fn lazy_static_value_template( + _comments: &str, + _name: &str, + _vtype: &str, + _value: &str, +) -> String { + todo!() +} + +pub fn integer_template(options: &ConversionOptions, comments: &str, name: &str) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![NameType { + name: name.to_string(), + ty: "INTEGER".to_string(), + is_primitive: true, + inner_types: None, + }], + name, + "INTEGER", + "etsi_its_primitives_conversion::toRos_INTEGER(in, out.value);", + "etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out);", + ) +} + +pub fn generalized_time_template(_comments: &str, _name: &str) -> String { + todo!(); +} + +pub fn utc_time_template(_comments: &str, _name: &str) -> String { + todo!(); +} + +pub fn bit_string_template(options: &ConversionOptions, comments: &str, name: &str) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![NameType { + name: name.to_string(), + ty: "BIT_STRING".to_string(), + is_primitive: true, + inner_types: None, + }], + name, + "BIT-STRING", + "etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value);\n \ + out.bits_unused = in.bits_unused;", + "etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out);\n \ + out.bits_unused = in.bits_unused;", + ) +} + +pub fn octet_string_template(options: &ConversionOptions, comments: &str, name: &str) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![NameType { + name: name.to_string(), + ty: "OCTET_STRING".to_string(), + is_primitive: true, + inner_types: None, + }], + name, + "OCTET-STRING", + "etsi_its_primitives_conversion::toRos_OCTET_STRING(in, out.value);", + "etsi_its_primitives_conversion::toStruct_OCTET_STRING(in.value, out);", + ) +} + +pub fn char_string_template( + options: &ConversionOptions, + comments: &str, + name: &str, + string_type: &str, +) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![NameType { + name: name.to_string(), + ty: string_type.to_string(), + is_primitive: true, + inner_types: None, + }], + name, + string_type, + &format!("etsi_its_primitives_conversion::toRos_{string_type}(in, out.value);"), + &format!("etsi_its_primitives_conversion::toStruct_{string_type}(in.value, out);"), + ) +} + +pub fn boolean_template(options: &ConversionOptions, comments: &str, name: &str) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![NameType { + name: name.to_string(), + ty: "BOOLEAN".to_string(), + is_primitive: true, + inner_types: None, + }], + name, + "BOOLEAN", + "etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value);", + "etsi_its_primitives_conversion::toStruct_BOOLEAN(in.value, out);", + ) +} + +pub fn primitive_value_template( + _comments: &str, + _name: &str, + _type_name: &str, + _assignment: &str, +) -> String { + todo!(); +} + +pub fn enum_value_template( + _comments: &str, + _name: &str, + _enumerated: &str, + _enumeral: &str, +) -> String { + todo!(); +} + +pub fn null_template(_comments: &str, _name: &str) -> String { + todo!(); +} + +pub fn any_template(_comments: &str, _name: &str) -> String { + todo!(); +} + +pub fn oid_template(_comments: &str, _name: &str) -> String { + todo!(); +} + +pub fn enumerated_template(options: &ConversionOptions, comments: &str, name: &str) -> String { + conversion_template( + comments, + &options.main_pdu, + &vec![], + name, + "ENUMERATED", + "out.value = in;", + "out = in.value;", + ) +} + +pub fn _sequence_or_set_value_template( + _comments: &str, + _name: &str, + _vtype: &str, + _members: &str, +) -> String { + todo!() +} + +#[allow(clippy::too_many_arguments)] +pub fn sequence_or_set_template( + options: &ConversionOptions, + comments: &str, + name: &str, + members: Vec, +) -> String { + let links: HashMap = members + .iter() + .filter_map(|m| { + if let Some(inner) = &m.name_type.inner_types { + match inner { + InnerTypes::Choice(c) => Some(( + c.linked_with.clone(), + members + .iter() + .find(|m| m.name_type.name == c.linked_with) + .unwrap(), + )), + } + } else { + None + } + }) + .collect(); + + // C -> ROS + let to_ros_inner_members = |member: &NamedSeqMember| -> String { + if let Some(inner) = &member.name_type.inner_types { + let cases = match inner { + InnerTypes::Choice(c) => { + c.options.iter().map(|im| { + format!(" case {name}__{c_field_name}_PR_{ty}:\n \ + toRos_{ty}(in.{c_field_name}.choice.{c_member}, out.{r_field_name}.{r_member});\n \ + out.{r_field_name}.choice.value = {pdu}_msgs::{linked_with}::{r_const_member};\n \ + break;", + pdu = &options.main_pdu, + linked_with = links.get(&c.linked_with).unwrap().name_type.ty, + c_field_name = member.name_type.name, + r_field_name = &to_ros_snake_case(&member.name_type.name), + ty = im.ty, + c_member = to_ros_title_case(&im.name), + r_member = to_ros_snake_case(&im.name), + r_const_member = to_ros_const_case(&im.name)) + }).collect::>().join("\n") + }, + }; + format!( + "switch (in.{field_name}.present) {{\n\ + {cases}\n \ + }}", + field_name = member.name_type.name, + cases = cases + ) + } else { + "".to_string() + } + }; + + let to_ros_conversion_call = |member: &NamedSeqMember| -> String { + if !member.name_type.is_primitive { + if member.name_type.inner_types.is_some() { + // TODO optional type with inner_types + to_ros_inner_members(&member) + } else { + format!( + "toRos_{ty}({deref}in.{c_member}, out.{r_member});", + ty = member.name_type.ty, + deref = if member.is_optional { "*" } else { "" }, + c_member = member.name_type.name, + r_member = to_ros_snake_case(&member.name_type.name) + ) + } + } else { + format!( + "etsi_its_primitives_conversion::toRos_{ty}({deref}in.{c_member}, out.{r_member});", + ty = member.name_type.ty, + deref = if member.is_optional { "*" } else { "" }, + c_member = member.name_type.name, + r_member = to_ros_snake_case(&member.name_type.name) + ) + } + }; + let to_ros_fmt_member = |member: &NamedSeqMember| -> String { + if member.is_optional { + format!( + "if (in.{c_member}) {{\n \ + {conversion}\n \ + {present}\ + }}", + c_member = member.name_type.name, + conversion = to_ros_conversion_call(&member), + present = if !member.has_default { + format!( + " out.{r_member}_is_present = true;\n ", + r_member = to_ros_snake_case(&member.name_type.name) + ) + } else { + "".to_string() + } + ) + } else { + to_ros_conversion_call(&member) + } + }; + let to_ros_members = members + .iter() + .map(|member| to_ros_fmt_member(&member)) + .collect::>() + .join("\n "); + + // ROS -> C + let to_c_inner_members = |member: &NamedSeqMember| -> String { + if let Some(inner) = &member.name_type.inner_types { + let cases = match inner { + InnerTypes::Choice(c) => { + c.options.iter().map(|im| { + format!(" case {pdu}_msgs::{linked_with}::{r_const_member}:\n \ + toStruct_{ty}(in.{r_field_name}.{r_member}, out.{c_field_name}.choice.{c_member});\n \ + out.{c_field_name}.present = {name}__{c_field_name}_PR::{name}__{c_field_name}_PR_{c_member};\n \ + break;", + pdu = &options.main_pdu, + linked_with = links.get(&c.linked_with).unwrap().name_type.ty, + c_field_name = member.name_type.name, + r_field_name = &to_ros_snake_case(&member.name_type.name), + ty = im.ty, + c_member = to_ros_title_case(&im.name), + r_member = to_ros_snake_case(&im.name), + r_const_member = to_ros_const_case(&im.name)) + }).collect::>().join("\n") + }, + }; + format!( + "switch (in.{field_name}.choice.value) {{\n\ + {cases}\n \ + }}", + field_name = to_ros_snake_case(&member.name_type.name), + cases = cases + ) + } else { + "".to_string() + } + }; + + let to_c_conversion_call = |member: &NamedSeqMember| -> String { + if !member.name_type.is_primitive { + if member.name_type.inner_types.is_some() { + // TODO optional type with inner_types + to_c_inner_members(&member) + } else { + format!( + "toStruct_{ty}(in.{r_member}, {deref}out.{c_member});", + ty = member.name_type.ty, + deref = if member.is_optional { "*" } else { "" }, + c_member = member.name_type.name, + r_member = to_ros_snake_case(&member.name_type.name) + ) + } + } else { + format!("etsi_its_primitives_conversion::toStruct_{ty}(in.{r_member}, {deref}out.{c_member});", + ty = member.name_type.ty, + deref = if member.is_optional { "*" } else { "" }, + c_member = member.name_type.name, + r_member = to_ros_snake_case(&member.name_type.name) + ) + } + }; + let to_c_fmt_member = |member: &NamedSeqMember| -> String { + if member.is_optional { + if !member.has_default { + format!( + "if (in.{r_member}_is_present) {{\n \ + out.{c_member} = ({ty}_t*) calloc(1, sizeof({ty}_t));\n \ + {conversion}\n \ + }}", + ty = member.name_type.ty, + c_member = member.name_type.name, + conversion = to_c_conversion_call(&member), + r_member = to_ros_snake_case(&member.name_type.name) + ) + } else { + format!( + "out.{c_member} = ({ty}_t*) calloc(1, sizeof({ty}_t));\n \ + {conversion}", + ty = member.name_type.ty, + c_member = member.name_type.name, + conversion = to_c_conversion_call(&member) + ) + } + } else { + to_c_conversion_call(&member) + } + }; + let to_c_members = members + .iter() + .map(|member| to_c_fmt_member(&member)) + .collect::>() + .join("\n "); + + let includes = &members + .iter() + .flat_map(|m| { + if let Some(inners) = &m.name_type.inner_types { + match inners { + InnerTypes::Choice(c) => c.options.clone(), + } + } else { + vec![m.name_type.clone()] + } + }) + .collect(); + + conversion_template( + comments, + &options.main_pdu, + &includes, + name, + "SEQUENCE", + &to_ros_members, + &to_c_members, + ) +} + +pub fn sequence_or_set_of_template( + options: &ConversionOptions, + _is_set_of: bool, + comments: &str, + name: &str, + _anonymous_item: &str, + member_type: &str, +) -> String { + let to_ros_loop = format!( + "for (int i = 0; i < in.list.count; ++i) {{\n \ + {pdu}_msgs::{ty} el;\n \ + toRos_{ty}(*(in.list.array[i]), el);\n \ + out.array.push_back(el);\n \ + }}", + pdu = &options.main_pdu, + ty = member_type + ); + + let to_c_loop = + format!("for (int i = 0; i < in.array.size(); ++i) {{\n \ + {ty}_t* el = ({ty}_t*) calloc(1, sizeof({ty}_t));\n \ + toStruct_{ty}(in.array[i], *el);\n \ + if (asn_sequence_add(&out, el)) throw std::invalid_argument(\"Failed to add to A_SEQUENCE_OF\");\n \ + }}", + ty = member_type); + + conversion_template( + comments, + &options.main_pdu, + &vec![ + NameType { + name: name.to_string(), + ty: name.to_string(), + is_primitive: false, + inner_types: None, + }, + NameType { + name: member_type.to_string(), + ty: member_type.to_string(), + is_primitive: false, + inner_types: None, + }, + ], + name, + "SEQUENCE-OF", + &to_ros_loop, + &to_c_loop, + ) +} + +pub fn choice_value_template( + _comments: &str, + _name: &str, + _type_id: &str, + _choice_name: &str, + _inner_decl: &str, +) -> String { + todo!(); +} + +pub fn const_choice_value_template( + _comments: &str, + _name: &str, + _type_id: &str, + _choice_name: &str, + _inner_decl: &str, +) -> String { + todo!(); +} + +pub fn choice_template( + options: &ConversionOptions, + comments: &str, + name: &str, + members: &Vec, +) -> String { + let to_ros_members = format!("switch (in.present) {{\n") + + &members + .iter() + .map(|member| { + if !member.is_primitive { + format!( + " case {parent}_PR_{c_member}:\n \ + toRos_{ty}(in.choice.{c_member}, out.{r_member});\n \ + out.choice = {pdu}_msgs::{parent}::CHOICE_{r_ch_member};", + parent = &name, + ty = member.ty, + pdu = &options.main_pdu, + c_member = member.name, + r_member = to_ros_snake_case(&member.name), + r_ch_member = to_ros_const_case(&member.name) + ) + } else { + format!( + "etsi_its_primitives_conversion::toRos_{ty}(in, out.value);", + ty = member.ty, + ) + } + }) + .collect::>() + .join("\n break;\n") + + "\n break;\n default: break;\n }"; + + let to_c_members = format!("switch (in.choice) {{\n") + + &members + .iter() + .map(|member| { + if !member.is_primitive { + format!( + " case {pdu}_msgs::{parent}::CHOICE_{r_ch_member}:\n \ + toStruct_{ty}(in.{r_member}, out.choice.{c_member});\n \ + out.present = {parent}_PR::{parent}_PR_{c_member};", + parent = &name, + ty = member.ty, + pdu = &options.main_pdu, + c_member = member.name, + r_member = to_ros_snake_case(&member.name), + r_ch_member = to_ros_const_case(&member.name) + ) + } else { + format!( + "etsi_its_primitives_conversion::toStruct_{ty}(in, out.value);", + ty = member.ty, + ) + } + }) + .collect::>() + .join("\n break;\n") + + "\n break;\n default: break;\n }"; + + conversion_template( + comments, + &options.main_pdu, + &members, + name, + "CHOICE", + &to_ros_members, + &to_c_members, + ) +} diff --git a/utils/codegen/docker/rgen/src/conversion/utils.rs b/utils/codegen/docker/rgen/src/conversion/utils.rs new file mode 100644 index 000000000..d89de6af4 --- /dev/null +++ b/utils/codegen/docker/rgen/src/conversion/utils.rs @@ -0,0 +1,410 @@ +use rasn_compiler::intermediate::{ + constraints::Constraint, + information_object::InformationObjectField, + types::{Choice, SequenceOrSet}, + ASN1Type, ASN1Value, CharacterStringType, IntegerType, +}; +use rasn_compiler::prelude::{ir::*, *}; + +use crate::common::{to_ros_title_case, IntegerTypeExt}; + +macro_rules! error { + ($kind:ident, $($arg:tt)*) => { + GeneratorError { + details: format!($($arg)*), + top_level_declaration: None, + kind: GeneratorErrorType::$kind, + } + }; +} + +pub(crate) use error; + +pub fn format_comments(comments: &str) -> Result { + if comments.is_empty() { + Ok("".into()) + } else { + let joined = String::from("// ") + &comments.replace('\n', "\n//") + "\n"; + Ok(joined) + } +} + +pub fn inner_name(name: &String, parent_name: &String) -> String { + format!("{}{}", parent_name, name) +} + +#[derive(Clone, Debug)] +pub struct NameType { + pub name: String, + pub ty: String, + pub is_primitive: bool, + pub inner_types: Option, +} + +#[derive(Clone, Debug)] +pub enum InnerTypes { + Choice(InnerTypesChoice), +} + +#[derive(Clone, Debug)] +pub struct InnerTypesChoice { + pub linked_with: String, + pub options: Vec, +} + +#[derive(Clone, Debug)] +pub struct NamedSeqMember { + pub name_type: NameType, + pub is_optional: bool, + pub has_default: bool, +} + +fn get_inner_types_names(ty: &ASN1Type) -> Option { + match ty { + ASN1Type::InformationObjectFieldReference(r) => { + if let Constraint::TableConstraint(ref tc) = r.constraints[0] { + let object_set = &tc.object_set; + let mut names = vec![]; + for value in &object_set.values { + if let ObjectSetValue::Inline(ref i) = value { + match i { + InformationObjectFields::DefaultSyntax(ds) => { + let mut name = "".to_string(); + let mut ty: ASN1Type = ASN1Type::Null; + ds.iter().for_each(|f| match f { + InformationObjectField::TypeField(f) => ty = f.ty.clone(), + InformationObjectField::FixedValueField(f) => { + name = value_to_tokens(&f.value, None).unwrap() + } + _ => todo!(), + }); + names.push(NameType { + name: name.clone(), + ty: constraints_and_type_name(&ty, &name, &"".to_string()) + .unwrap() + .1, + is_primitive: ty.is_builtin_type(), + inner_types: None, + }); + } + _ => todo!(), + } + } + } + let linked_with = tc + .linked_fields + .get(0) + .map(|f| f.field_name.clone()) + .unwrap_or_default(); + Some(InnerTypes::Choice(InnerTypesChoice { + linked_with, + options: names, + })) + } else { + unreachable!() + } + } + _ => None, + } +} + +pub fn get_sequence_or_set_members_names(sequence_or_set: &SequenceOrSet) -> Vec { + sequence_or_set + .members + .iter() + .map(|member| NamedSeqMember { + name_type: NameType { + name: member.name.clone(), + ty: constraints_and_type_name(&member.ty, &member.name, &"".to_string()) + .unwrap() + .1, + is_primitive: member.ty.is_builtin_type(), + inner_types: get_inner_types_names(&member.ty), + }, + is_optional: member.is_optional, + has_default: member.default_value.is_some(), + }) + .collect::>() +} + +pub fn get_choice_members_names(choice: &Choice) -> Vec { + choice + .options + .iter() + .map(|member| + NameType { + name: member.name.clone(), + ty: constraints_and_type_name(&member.ty, &member.name, &"".to_string()) + .unwrap() + .1, + is_primitive: member.ty.is_builtin_type(), + inner_types: None, + } + ).collect::>() +} + +fn constraints_and_type_name( + ty: &ASN1Type, + name: &String, + parent_name: &String, +) -> Result<(Vec, String), GeneratorError> { + Ok(match ty { + ASN1Type::Null => (vec![], "byte".into()), + ASN1Type::Boolean(b) => (b.constraints.clone(), "BOOLEAN".into()), + ASN1Type::Integer(i) => (i.constraints.clone(), "INTEGER".into()), + ASN1Type::Real(_) => (vec![], "float64".into()), + ASN1Type::ObjectIdentifier(_o) => todo!(), + ASN1Type::BitString(_b) => todo!(), + ASN1Type::OctetString(o) => (o.constraints.clone(), "uint8[]".into()), + ASN1Type::GeneralizedTime(_o) => todo!(), + ASN1Type::UTCTime(_o) => todo!(), + ASN1Type::Time(_t) => todo!(), + ASN1Type::CharacterString(c) => ( + c.constraints.clone(), + string_type(&c.ty).unwrap_or("STRING".into()), + ), + ASN1Type::Enumerated(_) + | ASN1Type::Choice(_) + | ASN1Type::Sequence(_) + | ASN1Type::SetOf(_) + | ASN1Type::Set(_) => (vec![], inner_name(name, parent_name)), + ASN1Type::SequenceOf(s) => { + let (_, inner_type) = constraints_and_type_name(&s.element_type, name, parent_name)?; + (s.constraints().clone(), format!("{inner_type}[]").into()) + } + ASN1Type::ElsewhereDeclaredType(e) => { + (e.constraints.clone(), to_ros_title_case(&e.identifier)) + } + ASN1Type::InformationObjectFieldReference(_) + | ASN1Type::EmbeddedPdv + | ASN1Type::External => { + let tx = &ty.constraints().unwrap()[0]; + let rname = if let Constraint::TableConstraint(ref tc) = tx { + tc.object_set + .values + .iter() + .find_map(|v| match v { + ObjectSetValue::Reference(ref r) => Some(r.clone()), + _ => None, + }) + .unwrap_or_default() + } else { + "".to_string() + }; + (vec![], rname) + } + ASN1Type::ChoiceSelectionType(_) => unreachable!(), + }) +} + +pub fn string_type(c_type: &CharacterStringType) -> Result { + match c_type { + CharacterStringType::NumericString => Ok("NumericString".into()), + CharacterStringType::VisibleString => Ok("VisibleString".into()), + CharacterStringType::IA5String => Ok("IA5String".into()), + CharacterStringType::TeletexString => Ok("TeletexString".into()), + CharacterStringType::VideotexString => Ok("VideotexString".into()), + CharacterStringType::GraphicString => Ok("GraphicString".into()), + CharacterStringType::GeneralString => Ok("GeneralString".into()), + CharacterStringType::UniversalString => Ok("UniversalString".into()), + CharacterStringType::UTF8String => Ok("UTF8String".into()), + CharacterStringType::BMPString => Ok("BMPString".into()), + CharacterStringType::PrintableString => Ok("PrintableString".into()), + } +} + +pub fn value_to_tokens( + value: &ASN1Value, + type_name: Option<&String>, +) -> Result { + match value { + ASN1Value::All => Err(error!( + NotYetInplemented, + "All values are currently unsupported!" + )), + ASN1Value::Null => todo!(), + ASN1Value::Choice { inner_value, .. } => { + if let Some(_ty_n) = type_name { + todo!() + } else { + Err(error!( + Unidentified, + "A type name is needed to stringify choice value {:?}", inner_value + )) + } + } + ASN1Value::OctetString(o) => { + let _bytes = o.iter().map(|byte| *byte); + todo!() + } + ASN1Value::SequenceOrSet(_) => Err(error!( + Unidentified, + "Unexpectedly encountered unlinked struct-like ASN1 value!" + )), + ASN1Value::LinkedStructLikeValue(fields) => { + if let Some(_ty_n) = type_name { + let _tokenized_fields = fields + .iter() + .map(|(_, _, val)| value_to_tokens(val.value(), None)) + .collect::, _>>()?; + todo!() + } else { + Err(error!( + Unidentified, + "A type name is needed to stringify sequence value {:?}", value + )) + } + } + ASN1Value::Boolean(b) => Ok(b.to_string()), + ASN1Value::Integer(i) => Ok(i.to_string()), + ASN1Value::String(s) => Ok(s.to_string()), + ASN1Value::Real(r) => Ok(r.to_string()), + ASN1Value::BitString(b) => { + let _bits = b.iter().map(|bit| bit.to_string()); + todo!() + } + ASN1Value::EnumeratedValue { + enumerated, + enumerable, + } => Ok(format!("{}_{}", enumerated, enumerable)), + ASN1Value::LinkedElsewhereDefinedValue { identifier: e, .. } + | ASN1Value::ElsewhereDeclaredValue { identifier: e, .. } => Ok(e.to_string()), + ASN1Value::ObjectIdentifier(oid) => { + let _arcs = oid + .0 + .iter() + .filter_map(|arc| arc.number.map(|id| id.to_string())); + todo!() + } + ASN1Value::Time(_t) => match type_name { + Some(_time_type) => todo!(), + None => todo!(), + }, + ASN1Value::LinkedArrayLikeValue(seq) => { + let _elems = seq + .iter() + .map(|v| value_to_tokens(v, None)) + .collect::, _>>()?; + todo!() + } + ASN1Value::LinkedNestedValue { + supertypes: _, + value, + } => Ok(value_to_tokens(value, type_name)?), + ASN1Value::LinkedIntValue { + integer_type, + value, + } => { + let val = *value; + match integer_type { + IntegerType::Unbounded => Ok(val.to_string()), + _ => Ok(val.to_string()), + } + } + ASN1Value::LinkedCharStringValue(string_type, value) => { + let _val = value; + match string_type { + CharacterStringType::NumericString => { + todo!() + } + CharacterStringType::VisibleString => { + todo!() + } + CharacterStringType::IA5String => { + todo!() + } + CharacterStringType::UTF8String => todo!(), + CharacterStringType::BMPString => { + todo!() + } + CharacterStringType::PrintableString => { + todo!() + } + CharacterStringType::GeneralString => { + todo!() + } + CharacterStringType::VideotexString + | CharacterStringType::GraphicString + | CharacterStringType::UniversalString + | CharacterStringType::TeletexString => Err(GeneratorError::new( + None, + &format!("{:?} values are currently unsupported!", string_type), + GeneratorErrorType::NotYetInplemented, + )), + } + } + } +} + +pub fn format_sequence_or_set_of_item_type( + type_name: String, + first_item: Option<&ASN1Value>, +) -> String { + match type_name { + name if name == NULL => todo!(), + name if name == BOOLEAN => "bool".into(), + name if name == INTEGER => { + match first_item { + Some(ASN1Value::LinkedIntValue { integer_type, .. }) => { + integer_type.to_str().into() + } + _ => "int64".into(), // best effort + } + } + name if name == BIT_STRING => "BitString".into(), + name if name == OCTET_STRING => "OctetString".into(), + name if name == GENERALIZED_TIME => "GeneralizedTime".into(), + name if name == UTC_TIME => "UtcTime".into(), + name if name == OBJECT_IDENTIFIER => "ObjectIdentifier".into(), + name if name == NUMERIC_STRING => "NumericString".into(), + name if name == VISIBLE_STRING => "VisibleString".into(), + name if name == IA5_STRING => "IA5String".into(), + name if name == UTF8_STRING => "UTF8String".into(), + name if name == BMP_STRING => "BMPString".into(), + name if name == PRINTABLE_STRING => "PrintableString".into(), + name if name == GENERAL_STRING => "GeneralString".into(), + name => name, + } +} + +trait ASN1ValueExt { + fn is_const_type(&self) -> bool; +} + +impl ASN1ValueExt for ASN1Value { + fn is_const_type(&self) -> bool { + match self { + ASN1Value::Null | ASN1Value::Boolean(_) | ASN1Value::EnumeratedValue { .. } => true, + ASN1Value::Choice { inner_value, .. } => inner_value.is_const_type(), + ASN1Value::LinkedIntValue { integer_type, .. } => { + integer_type != &IntegerType::Unbounded + } + ASN1Value::LinkedNestedValue { value, .. } => value.is_const_type(), + ASN1Value::LinkedElsewhereDefinedValue { can_be_const, .. } => *can_be_const, + _ => false, + } + } +} + +impl ASN1ValueExt for ASN1Type { + fn is_const_type(&self) -> bool { + match self { + ASN1Type::Null | ASN1Type::Enumerated(_) | ASN1Type::Boolean(_) => true, + ASN1Type::Integer(i) => { + i.constraints.iter().fold(IntegerType::Unbounded, |acc, c| { + acc.max_restrictive(c.integer_constraints()) + }) != IntegerType::Unbounded + } + ASN1Type::Choice(c) => c + .options + .iter() + .fold(true, |acc, opt| opt.ty.is_const_type() && acc), + ASN1Type::Set(s) | ASN1Type::Sequence(s) => s + .members + .iter() + .fold(true, |acc, m| m.ty.is_const_type() && acc), + ASN1Type::SetOf(s) | ASN1Type::SequenceOf(s) => s.element_type.is_const_type(), + _ => false, + } + } +} diff --git a/utils/codegen/docker/rgen/src/lib.rs b/utils/codegen/docker/rgen/src/lib.rs new file mode 100644 index 000000000..09dabbaeb --- /dev/null +++ b/utils/codegen/docker/rgen/src/lib.rs @@ -0,0 +1,3 @@ +mod common; +pub mod conversion; +pub mod msgs; diff --git a/utils/codegen/docker/rgen/src/msgs/bin.rs b/utils/codegen/docker/rgen/src/msgs/bin.rs new file mode 100644 index 000000000..9bacc5397 --- /dev/null +++ b/utils/codegen/docker/rgen/src/msgs/bin.rs @@ -0,0 +1,46 @@ +use std::path::PathBuf; + +use clap::Parser; +use regex::Regex; + +use rasn_compiler::prelude::*; +use ros_backend::msgs::Msgs; + +#[derive(Parser, Debug)] +struct Cli { + /// Main PDU name + #[clap(short, long)] + pdu: String, + #[clap(short, long)] + /// Output directory + out: std::path::PathBuf, + /// ASN.1 files to compile + paths: Vec, +} + +fn main() { + let args = Cli::parse(); + + // Compile ROS messages + let compiler_res = Compiler::new() + .with_backend(Msgs) + .add_asn_sources_by_path(args.paths.iter()) + .compile_to_string(); + let generated = &compiler_res.unwrap().generated; + + // Split generated code into individual messages + let re_name = Regex::new(r"##\s([\w-]+)\s(\w+)\b").unwrap(); + let re_def = Regex::new(r"\n((.|\n)*?)\n").unwrap(); + generated.split_inclusive("").for_each(|s| { + if let Some(def_caps) = re_def.captures(s) { + let definition = def_caps.get(1).unwrap().as_str(); + let name = if let Some(name_caps) = re_name.captures(definition) { + name_caps.get(2).unwrap().as_str() + } else { + "unknown" + }; + let path = args.out.join(format!("{}.msg", name)); + std::fs::write(path, definition).unwrap(); + } + }); +} diff --git a/utils/codegen/docker/rgen/src/msgs/builder.rs b/utils/codegen/docker/rgen/src/msgs/builder.rs new file mode 100644 index 000000000..b5029596d --- /dev/null +++ b/utils/codegen/docker/rgen/src/msgs/builder.rs @@ -0,0 +1,709 @@ +use std::{collections::BTreeMap, error::Error}; + +use rasn_compiler::prelude::ir::*; +use rasn_compiler::prelude::*; + +use crate::common::*; +use crate::msgs::{generate, Msgs}; +use crate::msgs::{template::*, utils::*}; + +pub(crate) const INNER_ARRAY_LIKE_PREFIX: &str = "Anonymous_"; + +impl Backend for Msgs { + fn generate_module( + &self, + tlds: Vec, + ) -> Result { + let tlds = merge_tlds(tlds); + let (pdus, warnings): (Vec, Vec>) = + tlds.into_iter() + .fold((vec![], vec![]), |mut acc, tld| match generate(tld) { + Ok(s) => { + s.len().gt(&0).then(|| { + acc.0.push(format!( + "\n\ + {s}\n\ + " + )) + }); + acc + } + Err(e) => { + acc.1.push(Box::new(e)); + acc + } + }); + Ok(GeneratedModule { + generated: Some(format!("{}", pdus.join("\n\n"))), + warnings, + }) + } +} + +pub fn merge_tlds(tlds: Vec) -> Vec { + let mut merged_tlds = Vec::::with_capacity(tlds.len()); + let mut merge_to = Vec::<(&ToplevelDefinition, &String)>::new(); + tlds.iter().for_each(|tld| { + if let ToplevelDefinition::Value(v) = &tld { + if let ASN1Value::LinkedIntValue { .. } = &v.value { + merge_to.push((&tld, &v.associated_type)); + } else { + merged_tlds.push(tld.clone()); + } + } else { + merged_tlds.push(tld.clone()); + } + }); + merge_to.iter().for_each(|(tld, ty)| { + for t in &mut merged_tlds { + if let ToplevelDefinition::Type(tt) = t { + if tt.name == **ty { + // Add value to type's distinguished values + if let ASN1Type::Integer(ref mut int) = tt.ty { + let value = match &tld { + ToplevelDefinition::Value(v) => { + if let ASN1Value::LinkedIntValue { + integer_type: _, + value, + } = &v.value + { + value + } else { + unreachable!() + } + } + _ => unreachable!(), + }; + match int.distinguished_values { + Some(ref mut dv) => dv.push(DistinguishedValue { + name: tld.name().clone(), + value: *value, + }), + None => { + int.distinguished_values = Some(vec![DistinguishedValue { + name: tld.name().clone(), + value: *value, + }]); + } + } + } + break; + } + } + } + }); + merged_tlds +} + +pub fn generate_typealias(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::ElsewhereDeclaredType(dec) = &tld.ty { + Ok(typealias_template( + &format_comments(&tld.comments)?, + &tld.name, + &dec.identifier, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected type alias top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_integer_value(tld: ToplevelValueDefinition) -> Result { + if let ASN1Value::LinkedIntValue { integer_type, .. } = tld.value { + let formatted_value = value_to_tokens(&tld.value, None)?; + let formatted_name = to_ros_const_case(&tld.name); + let ty = integer_type.to_str(); + if tld.associated_type == INTEGER { + Ok(lazy_static_value_template( + &format_comments(&tld.comments)?, + &formatted_name, + "int64", + &formatted_value, + )) + } else if integer_type.is_unbounded() { + Ok(lazy_static_value_template( + &format_comments(&tld.comments)?, + &formatted_name, + ty, + &formatted_value, + )) + } else { + Ok(integer_value_template( + &format_comments(&tld.comments)?, + &formatted_name, + ty, + &formatted_value, + )) + } + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Value(tld)), + "Expected INTEGER value top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_integer(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::Integer(ref int) = tld.ty { + Ok(integer_template( + &format_comments(&tld.comments)?, + &to_ros_title_case(&tld.name), + &format_constraints(true, &int.constraints)?, + int.int_type().to_str(), + &format_distinguished_values(&int.distinguished_values), + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected INTEGER top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_bit_string(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::BitString(ref bitstr) = tld.ty { + Ok(bit_string_template( + &format_comments(&tld.comments)?, + &tld.name, + &format_constraints(true, &bitstr.constraints)?, + &format_distinguished_values(&bitstr.distinguished_values), + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected BIT STRING top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_octet_string(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::OctetString(ref _oct_str) = tld.ty { + Ok(octet_string_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected OCTET STRING top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_character_string(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::CharacterString(ref char_str) = tld.ty { + Ok(char_string_template( + &format_comments(&tld.comments)?, + &tld.name, + &string_type(&char_str.ty)?, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected Character String top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_boolean(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::Boolean(_) = tld.ty { + Ok(boolean_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected BOOLEAN top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +macro_rules! call_template { + ($fn:ident, $tld:ident, $($args:expr),*) => { + Ok($fn( + &format_comments(&$tld.comments)?, + (&$tld.name), + $($args),* + )) + }; +} + +macro_rules! assignment { + ($unformatted:expr, $inner:expr) => {{ + let _ty = ($unformatted); + let _inner = $inner; + "quote!(#ty(#inner))".into() + }}; +} + +pub fn generate_value(tld: ToplevelValueDefinition) -> Result { + let ty = tld.associated_type.as_str(); + match &tld.value { + ASN1Value::Null if ty == NULL => { + call_template!( + primitive_value_template, + tld, + "quote!(())".into(), + "quote!(())".into() + ) + } + ASN1Value::Null => call_template!( + primitive_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, "byte null 0".to_string()) + ), + ASN1Value::Boolean(b) if ty == BOOLEAN => { + call_template!(primitive_value_template, tld, "bool", &b.to_string()) + } + ASN1Value::Boolean(b) => call_template!( + primitive_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, b.to_string()) + ), + ASN1Value::LinkedIntValue { .. } => generate_integer_value(tld), + ASN1Value::BitString(_) if ty == BIT_STRING => todo!(), + ASN1Value::OctetString(_) if ty == OCTET_STRING => todo!(), + ASN1Value::Choice { + variant_name, + inner_value, + .. + } => { + if inner_value.is_const_type() { + call_template!( + const_choice_value_template, + tld, + &tld.associated_type, + variant_name, + &value_to_tokens(inner_value, None)? + ) + } else { + call_template!( + choice_value_template, + tld, + &tld.associated_type, + &variant_name, + &value_to_tokens(inner_value, None)? + ) + } + } + ASN1Value::EnumeratedValue { + enumerated, + enumerable, + } => call_template!(enum_value_template, tld, enumerated, enumerable), + ASN1Value::Time(_) if ty == GENERALIZED_TIME => todo!(), + ASN1Value::Time(_) if ty == UTC_TIME => todo!(), + ASN1Value::LinkedStructLikeValue(s) => { + let _members = s + .iter() + .map(|(_, _, val)| value_to_tokens(val.value(), None)) + .collect::, _>>()?; + todo!() + } + ASN1Value::LinkedNestedValue { supertypes, value } => { + let parent = supertypes.last().map(|s| (s)); + if value.is_const_type() { + call_template!( + primitive_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) + ) + } else { + call_template!( + lazy_static_value_template, + tld, + &tld.associated_type, + assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) + ) + } + } + ASN1Value::ObjectIdentifier(_) if ty == OBJECT_IDENTIFIER => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == NUMERIC_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == VISIBLE_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == IA5_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == UTF8_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == BMP_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == PRINTABLE_STRING => todo!(), + ASN1Value::LinkedCharStringValue(_, _) if ty == GENERAL_STRING => todo!(), + ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SEQUENCE_OF) => { + let _item_type = format_sequence_or_set_of_item_type( + ty.replace(SEQUENCE_OF, "").trim().to_string(), + s.first().map(|i| &**i), + ); + todo!() + } + ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SET_OF) => { + let _item_type = format_sequence_or_set_of_item_type( + ty.replace(SET_OF, "").trim().to_string(), + s.first().map(|i| &**i), + ); + todo!() + } + ASN1Value::BitString(_) + | ASN1Value::Time(_) + | ASN1Value::LinkedCharStringValue(_, _) + | ASN1Value::ObjectIdentifier(_) + | ASN1Value::LinkedArrayLikeValue(_) + | ASN1Value::ElsewhereDeclaredValue { .. } + | ASN1Value::OctetString(_) => call_template!( + lazy_static_value_template, + tld, + &tld.associated_type.to_string(), + assignment!(&tld.associated_type, value_to_tokens(&tld.value, None)?) + ), + _ => Ok("".to_string()), + } +} + +pub fn generate_any(tld: ToplevelTypeDefinition) -> Result { + Ok(any_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) +} + +pub fn generate_generalized_time(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::GeneralizedTime(_) = &tld.ty { + Ok(generalized_time_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected GeneralizedTime top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_utc_time(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::UTCTime(_) = &tld.ty { + Ok(utc_time_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected UTCTime top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_oid(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::ObjectIdentifier(_oid) = &tld.ty { + Ok(oid_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected OBJECT IDENTIFIER top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_null(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::Null = tld.ty { + Ok(null_template( + &format_comments(&tld.comments)?, + &tld.name, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected NULL top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_enumerated(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::Enumerated(ref enumerated) = tld.ty { + let extensible = enumerated + .extensible + .map(|_| ".extensible".into()) + .unwrap_or_default(); + Ok(enumerated_template( + &format_comments(&tld.comments)?, + &tld.name, + extensible, + &format_enum_members(enumerated), + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected ENUMERATED top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_choice(tld: ToplevelTypeDefinition) -> Result { + if let ASN1Type::Choice(ref choice) = tld.ty { + let inner_options = format_nested_choice_options(choice, &tld.name)?; + let extensible = choice + .extensible + .map(|_| ".extensible".into()) + .unwrap_or_default(); + Ok(choice_template( + &format_comments(&tld.comments)?, + &tld.name, + extensible, + &format_choice_options(choice, &tld.name)?, + inner_options, + "", + )) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected CHOICE top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} + +pub fn generate_sequence_or_set(tld: ToplevelTypeDefinition) -> Result { + match tld.ty { + ASN1Type::Sequence(ref seq) | ASN1Type::Set(ref seq) => { + let extensible = seq + .extensible + .map(|_| ".extensible".into()) + .unwrap_or_default(); + let declaration = format_sequence_or_set_members(seq, &tld.name)?; + Ok(sequence_or_set_template( + &format_comments(&tld.comments)?, + &tld.name, + extensible, + &declaration, + format_nested_sequence_members(seq, &tld.name)?, + "", + &format_default_methods(&seq.members, &tld.name)?, + "", + )) + } + _ => Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected SEQUENCE top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )), + } +} + +pub fn generate_sequence_or_set_of(tld: ToplevelTypeDefinition) -> Result { + let (is_set_of, seq_or_set_of) = match &tld.ty { + ASN1Type::SetOf(se_of) => (true, se_of), + ASN1Type::SequenceOf(se_of) => (false, se_of), + _ => { + return Err(GeneratorError::new( + Some(ToplevelDefinition::Type(tld)), + "Expected SEQUENCE OF top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } + }; + let anonymous_item = match seq_or_set_of.element_type.as_ref() { + ASN1Type::ElsewhereDeclaredType(_) => None, + n => Some(generate(ToplevelDefinition::Type( + ToplevelTypeDefinition { + parameterization: None, + comments: format!( + " Anonymous {} OF member ", + if is_set_of { "SET" } else { "SEQUENCE" } + ), + name: String::from(INNER_ARRAY_LIKE_PREFIX) + &tld.name, + ty: n.clone(), + tag: None, + index: None, + }, + ))?), + } + .unwrap_or_default(); + let member_type = match seq_or_set_of.element_type.as_ref() { + ASN1Type::ElsewhereDeclaredType(d) => d.identifier.clone(), + _ => format!("Anonymous{}", &tld.name), + }; + let constraints = format_constraints(true, &seq_or_set_of.constraints)?; + Ok(sequence_or_set_of_template( + is_set_of, + &format_comments(&tld.comments)?, + &tld.name, + &anonymous_item, + &member_type, + &constraints, + )) +} + +pub fn generate_information_object_set( + tld: ToplevelInformationDefinition, +) -> Result { + if let ASN1Information::ObjectSet(o) = &tld.value { + let class: &InformationObjectClass = match tld.class { + Some(ClassLink::ByReference(ref c)) => c, + _ => { + return Err(GeneratorError::new( + None, + "Missing class link in Information Object Set", + GeneratorErrorType::MissingClassKey, + )) + } + }; + let mut keys_to_types = o + .values + .iter() + .map(|v| match v { + ObjectSetValue::Reference(r) => Err(GeneratorError::new( + None, + &format!("Could not resolve reference of Information Object Set {r}"), + GeneratorErrorType::MissingClassKey, + )), + ObjectSetValue::Inline(InformationObjectFields::CustomSyntax(_)) => { + Err(GeneratorError::new( + Some(ToplevelDefinition::Information(tld.clone())), + "Unexpectedly encountered unresolved custom syntax!", + GeneratorErrorType::MissingClassKey, + )) + } + ObjectSetValue::Inline(InformationObjectFields::DefaultSyntax(s)) => { + resolve_standard_syntax(class, s) + } + }) + .collect::)>, _>>()?; + let mut choices = BTreeMap::>::new(); + for (key, items) in keys_to_types.drain(..) { + for (index, item) in items { + let id = class + .fields + .get(index) + .map(|f| f.identifier.identifier()) + .ok_or_else(|| GeneratorError { + top_level_declaration: Some(ToplevelDefinition::Information(tld.clone())), + details: "Could not find class field for index.".into(), + kind: GeneratorErrorType::SyntaxMismatch, + })?; + match choices.get_mut(id) { + Some(entry) => entry.push((key.clone(), item)), + None => { + choices.insert(id.clone(), vec![(key.clone(), item)]); + } + } + } + } + + if choices.is_empty() { + for InformationObjectClassField { identifier, .. } in &class.fields { + choices.insert(identifier.identifier().clone(), Vec::new()); + } + } + + let name = &tld.name; + let class_unique_id_type = class + .fields + .iter() + .find_map(|f| (f.is_unique).then(|| f.ty.clone())) + .flatten() + .ok_or_else(|| GeneratorError { + top_level_declaration: None, + details: "Could not determine unique class identifier type.".into(), + kind: GeneratorErrorType::SyntaxMismatch, + })?; + let class_unique_id_type_name = type_to_tokens(&class_unique_id_type)?; + + let mut field_enums = vec![]; + for (_field_name, fields) in choices.iter() { + let field_enum_name = name.clone(); + let mut ids = vec![]; + for (index, (id, ty)) in fields.iter().enumerate() { + let identifier_value = match id { + ASN1Value::LinkedElsewhereDefinedValue { + can_be_const: false, + .. + } => { + let _tokenized_value = + value_to_tokens(id, Some(&class_unique_id_type_name))?; + "quote!(*#tokenized_value)".into() + } + ASN1Value::LinkedNestedValue { value, .. } + if matches![ + &**value, + ASN1Value::LinkedElsewhereDefinedValue { + can_be_const: false, + .. + } + ] => + { + let _tokenized_value = + value_to_tokens(value, Some(&class_unique_id_type_name))?; + "quote!(*#tokenized_value)".into() + } + ASN1Value::LinkedNestedValue { value, .. } + if matches![&**value, ASN1Value::LinkedElsewhereDefinedValue { .. }] => + { + value_to_tokens(value, Some(&class_unique_id_type_name))? + } + _ => value_to_tokens(id, Some(&class_unique_id_type_name))?, + }; + let type_id = type_to_tokens(ty).unwrap_or("type?".into()); + let variant_name = match id { + ASN1Value::LinkedElsewhereDefinedValue { + identifier: ref_id, .. + } + | ASN1Value::ElsewhereDeclaredValue { + identifier: ref_id, .. + } => ref_id.clone(), + _ => format!("{field_enum_name}_{index}"), + }; + if ty.constraints().map_or(true, |c| c.is_empty()) { + ids.push((variant_name, type_id, identifier_value)); + } + } + + let variants = ids.iter().map(|(variant_name, type_id, _)| { + format!("{type_id} {}", to_ros_snake_case(variant_name)) + }); + + field_enums.push(format!( + "## OPEN-TYPE {field_enum_name}\n{class_unique_id_type_name} choice\n{}", + variants.fold("".to_string(), |mut acc, v| { + acc.push_str(&v); + acc.push_str("\n"); + acc + }), + )); + } + + Ok(field_enums.join("\n")) + } else { + Err(GeneratorError::new( + Some(ToplevelDefinition::Information(tld)), + "Expected Object Set top-level declaration", + GeneratorErrorType::Asn1TypeMismatch, + )) + } +} diff --git a/utils/codegen/docker/rgen/src/msgs/mod.rs b/utils/codegen/docker/rgen/src/msgs/mod.rs new file mode 100644 index 000000000..3bde1ca4a --- /dev/null +++ b/utils/codegen/docker/rgen/src/msgs/mod.rs @@ -0,0 +1,51 @@ +use rasn_compiler::prelude::ir::{ASN1Information, ASN1Type}; +use rasn_compiler::prelude::*; + +mod builder; +mod template; +mod utils; + +pub struct Msgs; + +use builder::*; + +fn generate(tld: ToplevelDefinition) -> Result { + match tld { + ToplevelDefinition::Type(t) => { + if t.parameterization.is_some() { + return Ok("".into()); + } + match t.ty { + ASN1Type::Null => generate_null(t), + ASN1Type::Boolean(_) => generate_boolean(t), + ASN1Type::Integer(_) => generate_integer(t), + ASN1Type::Enumerated(_) => generate_enumerated(t), + ASN1Type::BitString(_) => generate_bit_string(t), + ASN1Type::CharacterString(_) => generate_character_string(t), + ASN1Type::Sequence(_) | ASN1Type::Set(_) => generate_sequence_or_set(t), + ASN1Type::SequenceOf(_) | ASN1Type::SetOf(_) => generate_sequence_or_set_of(t), + ASN1Type::ElsewhereDeclaredType(_) => generate_typealias(t), + ASN1Type::Choice(_) => generate_choice(t), + ASN1Type::OctetString(_) => generate_octet_string(t), + ASN1Type::Time(_) => unimplemented!("rasn does not support TIME types yet!"), + ASN1Type::Real(_) => Err(GeneratorError { + kind: GeneratorErrorType::NotYetInplemented, + details: "Real types are currently unsupported!".into(), + top_level_declaration: None, + }), + ASN1Type::ObjectIdentifier(_) => generate_oid(t), + ASN1Type::InformationObjectFieldReference(_) + | ASN1Type::EmbeddedPdv + | ASN1Type::External => generate_any(t), + ASN1Type::GeneralizedTime(_) => generate_generalized_time(t), + ASN1Type::UTCTime(_) => generate_utc_time(t), + ASN1Type::ChoiceSelectionType(_) => unreachable!(), + } + } + ToplevelDefinition::Value(v) => generate_value(v), + ToplevelDefinition::Information(i) => match i.value { + ASN1Information::ObjectSet(_) => generate_information_object_set(i), + _ => Ok("".into()), + }, + } +} diff --git a/utils/codegen/docker/rgen/src/msgs/template.rs b/utils/codegen/docker/rgen/src/msgs/template.rs new file mode 100644 index 000000000..14283a48d --- /dev/null +++ b/utils/codegen/docker/rgen/src/msgs/template.rs @@ -0,0 +1,230 @@ +pub fn typealias_template(comments: &str, name: &str, alias: &str, annotations: &str) -> String { + format!( + "## TYPE-ALIAS {name}\n\ + {comments}\n\ + {alias} value\n\ + {annotations}" + ) +} + +pub fn integer_value_template(comments: &str, name: &str, vtype: &str, value: &str) -> String { + format!( + "## INTEGER-DEF {name}\n\ + {comments}\n\ + {vtype} {name} = {value}" + ) +} + +pub fn lazy_static_value_template(comments: &str, name: &str, vtype: &str, value: &str) -> String { + format!( + "## VALUE {name}\n\ + {comments}\n\ + {vtype} value = {value}" + ) +} + +pub fn integer_template( + comments: &str, + name: &str, + constraints: &str, + integer_type: &str, + dvalues: &str, +) -> String { + let typed_dvalues = dvalues + .replace("{type}", &integer_type) + .replace("{prefix}", ""); + format!( + "## INTEGER {name}\n\ + {comments}\n\ + {integer_type} value\n\n\ + {constraints}\n\n\ + {typed_dvalues}" + ) +} + +pub fn generalized_time_template(_comments: &str, _name: &str, _annotations: &str) -> String { + todo!(); +} + +pub fn utc_time_template(_comments: &str, _name: &str, _annotations: &str) -> String { + todo!(); +} + +pub fn bit_string_template(comments: &str, name: &str, constraints: &str, dvalues: &str) -> String { + let typed_dvalues = dvalues + .replace("{type}", "uint8") + .replace("{prefix}", "BIT_INDEX_"); + format!( + "## BIT-STRING {name}\n\ + {comments}\n\ + uint8[] value\n\ + uint8 bits_unused\n\ + {constraints}\n\n\ + {typed_dvalues}" + ) +} + +pub fn octet_string_template(comments: &str, name: &str, annotations: &str) -> String { + format!( + "## OCTET-STRING {name}\n\ + {comments}\n\ + uint8[] value\n\ + {annotations}" + ) +} + +pub fn char_string_template( + comments: &str, + name: &str, + string_type: &str, + annotations: &str, +) -> String { + format!( + "## {string_type} {name}\n\ + {comments}\n\ + string value\n\ + {annotations}" + ) +} + +pub fn boolean_template(comments: &str, name: &str, annotations: &str) -> String { + format!( + "## BOOLEAN {name}\n\ + {comments}\n\ + bool value\n\ + {annotations}" + ) +} + +pub fn primitive_value_template( + _comments: &str, + _name: &str, + _type_name: &str, + _assignment: &str, +) -> String { + todo!(); +} + +pub fn enum_value_template( + _comments: &str, + _name: &str, + _enumerated: &str, + _enumeral: &str, +) -> String { + todo!(); +} + +pub fn null_template(_comments: &str, _name: &str, _annotations: &str) -> String { + todo!(); +} + +pub fn any_template(_comments: &str, _name: &str, _annotations: &str) -> String { + todo!(); +} + +pub fn oid_template(_comments: &str, _name: &str, _annotations: &str) -> String { + todo!(); +} + +pub fn enumerated_template( + comments: &str, + name: &str, + extensible: &str, + enum_members: &str, + annotations: &str, +) -> String { + format!( + "## ENUMERATED {name} {extensible}\n\ + {comments}\n\ + uint8 value\n\ + {enum_members}\n\ + {annotations}" + ) +} + +pub fn _sequence_or_set_value_template( + _comments: &str, + _name: &str, + _vtype: &str, + _members: &str, +) -> String { + todo!() +} + +#[allow(clippy::too_many_arguments)] +pub fn sequence_or_set_template( + comments: &str, + name: &str, + extensible: &str, + members: &str, + nested_members: Vec, + annotations: &str, + default_methods: &str, + class_fields: &str, +) -> String { + format!( + "## SEQUENCE {name} {extensible}\n\ + {comments}\n\ + {members}\n\ + {}\n\ + {annotations}\n\ + {default_methods}\n\ + {class_fields}", + nested_members.join("\n") + ) +} + +pub fn sequence_or_set_of_template( + _is_set_of: bool, + comments: &str, + name: &str, + _anonymous_item: &str, + member_type: &str, + constraints: &str, +) -> String { + format!( + "## SEQUENCE-OF {name}\n\ + {comments}\n\ + {member_type}[] array\n\ + {constraints}" + ) +} + +pub fn choice_value_template( + _comments: &str, + _name: &str, + _type_id: &str, + _choice_name: &str, + _inner_decl: &str, +) -> String { + todo!(); +} + +pub fn const_choice_value_template( + _comments: &str, + _name: &str, + _type_id: &str, + _choice_name: &str, + _inner_decl: &str, +) -> String { + todo!(); +} + +pub fn choice_template( + comments: &str, + name: &str, + extensible: &str, + options: &str, + nested_options: Vec, + annotations: &str, +) -> String { + format!( + "## CHOICE {name} {extensible}\n\ + {comments}\n\ + uint8 choice\n\n\ + {options}\n\ + {}\n\ + {annotations}", + nested_options.join("\n") + ) +} diff --git a/utils/codegen/docker/rgen/src/msgs/utils.rs b/utils/codegen/docker/rgen/src/msgs/utils.rs new file mode 100644 index 000000000..e3b659ac9 --- /dev/null +++ b/utils/codegen/docker/rgen/src/msgs/utils.rs @@ -0,0 +1,781 @@ +use crate::common::{to_ros_const_case, to_ros_snake_case, to_ros_title_case, IntegerTypeExt}; +use rasn_compiler::intermediate::{ + constraints::Constraint, + encoding_rules::per_visible::{ + per_visible_range_constraints, CharsetSubset, PerVisibleAlphabetConstraints, + }, + information_object::{InformationObjectClass, InformationObjectField}, + types::{Choice, ChoiceOption, Enumerated, SequenceOrSet, SequenceOrSetMember}, + ASN1Type, ASN1Value, CharacterStringType, IntegerType, ToplevelDefinition, + ToplevelTypeDefinition, +}; +use rasn_compiler::prelude::{ir::*, *}; + +macro_rules! error { + ($kind:ident, $($arg:tt)*) => { + GeneratorError { + details: format!($($arg)*), + top_level_declaration: None, + kind: GeneratorErrorType::$kind, + } + }; +} + +pub(crate) use error; + +use super::*; + +pub fn inner_name(name: &String, parent_name: &String) -> String { + format!("{}{}", parent_name, name) +} + +pub fn int_type_token(opt_min: Option, opt_max: Option, is_extensible: bool) -> String { + if let (Some(min), Some(max)) = (opt_min, opt_max) { + format!( + "{}", + if is_extensible { + "int64" + } else if min >= 0 { + match max { + r if r <= u8::MAX.into() => "uint8", + r if r <= u16::MAX.into() => "uint16", + r if r <= u32::MAX.into() => "uint32", + r if r <= u64::MAX.into() => "uint64", + _ => "uint64", + } + } else { + match (min, max) { + (mi, ma) if mi >= i8::MIN.into() && ma <= i8::MAX.into() => "int8", + (mi, ma) if mi >= i16::MIN.into() && ma <= i16::MAX.into() => "int16", + (mi, ma) if mi >= i32::MIN.into() && ma <= i32::MAX.into() => "int32", + (mi, ma) if mi >= i64::MIN.into() && ma <= i64::MAX.into() => "int64", + _ => "int64", + } + } + ) + } else { + format!("int64") + } +} + +pub fn format_comments(comments: &str) -> Result { + if comments.is_empty() { + Ok("".into()) + } else { + let joined = String::from("# ") + &comments.replace('\n', "\n#") + "\n"; + Ok(joined) + } +} + +pub fn format_constraints( + signed: bool, + constraints: &Vec, +) -> Result { + if constraints.is_empty() { + return Ok("".into()); + } + let per_constraints = per_visible_range_constraints(signed, constraints)?; + let range_type = int_type_token( + per_constraints.min::(), + per_constraints.max::(), + per_constraints.is_extensible(), + ); + let range_prefix = if per_constraints.is_size_constraint() { + "LENGTH" + } else { + "VALUE" + }; + // handle default size constraints + if per_constraints.is_size_constraint() + && !per_constraints.is_extensible() + && per_constraints.min::() == Some(0) + && per_constraints.max::().is_none() + { + return Ok("".into()); + } + Ok( + match ( + per_constraints.min::(), + per_constraints.max::(), + per_constraints.is_extensible(), + ) { + (Some(min), Some(max), true) if min == max => { + format!( + "{range_type} {range_prefix}_MIN = {min}\n\ + {range_type} {range_prefix}_MAX = {max}" + ) + } + (Some(min), Some(max), true) => { + format!( + "{range_type} {range_prefix}_MIN = {min}\n\ + {range_type} {range_prefix}_MAX = {max}" + ) + } + (Some(min), Some(max), false) if min == max => { + format!("{range_type} {range_prefix} = {min}") + } + (Some(min), Some(max), false) => { + format!( + "{range_type} {range_prefix}_MIN = {min}\n\ + {range_type} {range_prefix}_MAX = {max}" + ) + } + (Some(min), None, true) => { + format!("{range_type} {range_prefix}_MIN = {min}") + } + (Some(min), None, false) => { + format!("{range_type} {range_prefix}_MIN = {min}") + } + (None, Some(max), true) => { + format!("{range_type} {range_prefix}_MAX = {max}") + } + (None, Some(max), false) => { + format!("{range_type} {range_prefix}_MAX = {max}") + } + _ => "".into(), + }, + ) +} + +pub fn format_distinguished_values(dvalues: &Option>) -> String { + let mut result = String::from(""); + if let Some(dvalues) = dvalues { + dvalues.iter().for_each(|dvalue| { + result.push_str(&format!( + "{{type}} {{prefix}}{} = {}\n", + to_ros_const_case(&dvalue.name), + dvalue.value + )); + }); + } + result +} + +pub fn _format_alphabet_annotations( + string_type: CharacterStringType, + constraints: &Vec, +) -> Result { + if constraints.is_empty() { + return Ok("".into()); + } + let mut permitted_alphabet = PerVisibleAlphabetConstraints::default_for(string_type); + for c in constraints { + if let Some(mut p) = PerVisibleAlphabetConstraints::try_new(c, string_type)? { + permitted_alphabet += &mut p + } + } + permitted_alphabet.finalize(); + let alphabet_unicode = permitted_alphabet + .charset_subsets() + .iter() + .map(|subset| match subset { + CharsetSubset::Single(c) => format!("{}", c.escape_unicode()), + CharsetSubset::Range { from, to } => format!( + "{}..{}", + from.map_or(String::from(""), |c| format!("{}", c.escape_unicode())), + to.map_or(String::from(""), |c| format!("{}", c.escape_unicode())) + ), + }) + .collect::>() + .join(", "); + Ok(if alphabet_unicode.is_empty() { + "".into() + } else { + "from(#alphabet_unicode)".into() + }) +} + +pub fn format_enum_members(enumerated: &Enumerated) -> String { + let first_extension_index = enumerated.extensible; + enumerated + .members + .iter() + .enumerate() + .map(|(i, e)| { + let name = to_ros_const_case(&e.name); + let index = e.index; + let extension = if i >= first_extension_index.unwrap_or(usize::MAX) { + "# .extended\n".to_string() + } else { + "".to_string() + }; + String::from(&format!("{extension}uint8 {name} = {index}")) + }) + .fold("".to_string(), |mut acc, e| { + acc.push_str(&e); + acc.push_str("\n"); + acc + }) +} + +pub fn format_sequence_or_set_members( + sequence_or_set: &SequenceOrSet, + parent_name: &String, +) -> Result { + let first_extension_index = sequence_or_set.extensible; + sequence_or_set + .members + .iter() + .enumerate() + .try_fold("".to_string(), |mut acc, (i, m)| { + let extension_annotation = if i >= first_extension_index.unwrap_or(usize::MAX) + && m.name.starts_with("ext_group_") + { + "extension_addition_group".into() + } else if i >= first_extension_index.unwrap_or(usize::MAX) { + "quote!(extension_addition)".into() + } else { + "".into() + }; + format_sequence_member(m, parent_name, extension_annotation).map(|declaration| { + acc.push_str(&format!("{declaration}")); + acc + }) + }) +} + +fn format_sequence_member( + member: &SequenceOrSetMember, + parent_name: &String, + _extension_annotation: String, +) -> Result { + let name = &member.name; + let (mut all_constraints, mut formatted_type_name) = + constraints_and_type_name(&member.ty, &member.name, parent_name)?; + all_constraints.append(&mut member.constraints.clone()); + let name = to_ros_snake_case(name); + if (member.is_optional && member.default_value.is_none()) + || member.name.starts_with("ext_group_") + { + formatted_type_name = format!( + "bool {name}_is_present\n\ + {formatted_type_name}" + ) + } + Ok(format!("{formatted_type_name} {name}\n")) +} + +pub fn format_choice_options( + choice: &Choice, + parent_name: &String, +) -> Result { + let first_extension_index = choice.extensible; + let options = choice + .options + .iter() + .enumerate() + .map(|(i, o)| { + let extension_annotation = if i >= first_extension_index.unwrap_or(usize::MAX) + && o.name.starts_with("ext_group_") + { + "quote!(extension_addition_group)".into() + } else if i >= first_extension_index.unwrap_or(usize::MAX) { + "quote!(extension_addition)".into() + } else { + "".into() + }; + let name = o.name.clone(); + format_choice_option(name, o, parent_name, i, extension_annotation) + }) + .collect::, _>>()?; + let folded_options = options.iter().fold( + ("".to_string(), "".to_string()), + |mut acc, (declaration, valset)| { + acc.0.push_str(&format!("{declaration}\n")); + acc.1.push_str(&format!("{valset}\n")); + acc + }, + ); + Ok(format!("{}\n{}", folded_options.0, folded_options.1)) +} + +fn format_choice_option( + name: String, + member: &ChoiceOption, + parent_name: &String, + index: usize, + _extension_annotation: String, +) -> Result<(String, String), GeneratorError> { + let (_, formatted_type_name) = + constraints_and_type_name(&member.ty, &member.name, parent_name)?; + let choice_type = format!("{formatted_type_name} {}", to_ros_snake_case(&name)); + let choice_selector = format!("uint8 CHOICE_{} = {index}", to_ros_const_case(&name)); + Ok((choice_type, choice_selector)) +} + +fn constraints_and_type_name( + ty: &ASN1Type, + name: &String, + parent_name: &String, +) -> Result<(Vec, String), GeneratorError> { + Ok(match ty { + ASN1Type::Null => (vec![], "byte".into()), + ASN1Type::Boolean(b) => (b.constraints.clone(), "bool".into()), + ASN1Type::Integer(i) => { + let per_constraints = per_visible_range_constraints(true, &i.constraints)?; + ( + i.constraints.clone(), + int_type_token( + per_constraints.min(), + per_constraints.max(), + per_constraints.is_extensible(), + ), + ) + } + ASN1Type::Real(_) => (vec![], "float64".into()), + ASN1Type::ObjectIdentifier(_o) => todo!(), + ASN1Type::BitString(_b) => todo!(), + ASN1Type::OctetString(o) => (o.constraints.clone(), "uint8[]".into()), + ASN1Type::GeneralizedTime(_o) => todo!(), + ASN1Type::UTCTime(_o) => todo!(), + ASN1Type::Time(_t) => todo!(), + ASN1Type::CharacterString(c) => (c.constraints.clone(), "string".into()), + ASN1Type::Enumerated(_) + | ASN1Type::Choice(_) + | ASN1Type::Sequence(_) + | ASN1Type::SetOf(_) + | ASN1Type::Set(_) => (vec![], inner_name(name, parent_name)), + ASN1Type::SequenceOf(s) => { + let (_, inner_type) = constraints_and_type_name(&s.element_type, name, parent_name)?; + (s.constraints().clone(), format!("{inner_type}[]").into()) + } + ASN1Type::ElsewhereDeclaredType(e) => { + (e.constraints.clone(), to_ros_title_case(&e.identifier)) + } + ASN1Type::InformationObjectFieldReference(_) + | ASN1Type::EmbeddedPdv + | ASN1Type::External => { + let tx = &ty.constraints().unwrap()[0]; + let rname = if let Constraint::TableConstraint(ref tc) = tx { + let v = &tc.object_set.values[0]; + if let ObjectSetValue::Reference(ref r) = v { + r.clone() + } else { + "".to_string() + } + } else { + "".to_string() + }; + (vec![], rname) + } + ASN1Type::ChoiceSelectionType(_) => unreachable!(), + }) +} + +pub fn string_type(c_type: &CharacterStringType) -> Result { + match c_type { + CharacterStringType::NumericString => Ok("NumericString".into()), + CharacterStringType::VisibleString => Ok("VisibleString".into()), + CharacterStringType::IA5String => Ok("Ia5String".into()), + CharacterStringType::TeletexString => Ok("TeletexString".into()), + CharacterStringType::VideotexString => Ok("VideotexString".into()), + CharacterStringType::GraphicString => Ok("GraphicString".into()), + CharacterStringType::GeneralString => Ok("GeneralString".into()), + CharacterStringType::UniversalString => Ok("UniversalString".into()), + CharacterStringType::UTF8String => Ok("Utf8String".into()), + CharacterStringType::BMPString => Ok("BmpString".into()), + CharacterStringType::PrintableString => Ok("PrintableString".into()), + } +} + +pub fn format_default_methods( + members: &Vec, + _parent_name: &str, +) -> Result { + let mut output = "".to_string(); + for member in members { + if let Some(value) = member.default_value.as_ref() { + let val = match value { + ASN1Value::EnumeratedValue { .. } => continue, /* TODO */ + _ => value_to_tokens(value, Some(&type_to_tokens(&member.ty)?.to_string()))?, + }; + // TODO generalize + let ty = match value { + ASN1Value::LinkedNestedValue { + supertypes: _, + value, + } => match value.as_ref() { + ASN1Value::LinkedIntValue { + integer_type, + value: _, + } => integer_type.to_str().to_string(), + _ => type_to_tokens(&member.ty)?, + }, + ASN1Value::EnumeratedValue { .. } => "uint8".into(), + _ => type_to_tokens(&member.ty)?, + }; + let method_name = format!("{}_DEFAULT", to_ros_const_case(&member.name)); + output.push_str(&format!("{ty} {method_name} = {val}\n")); + } + } + Ok(output) +} + +pub fn type_to_tokens(ty: &ASN1Type) -> Result { + match ty { + ASN1Type::Null => todo!(), + ASN1Type::Boolean(_) => Ok("bool".into()), + ASN1Type::Integer(i) => Ok(i.int_type().to_str().to_string()), + ASN1Type::Real(_) => Ok("float64".into()), + ASN1Type::BitString(_) => Ok("BitString".into()), + ASN1Type::OctetString(_) => Ok("OctetString".into()), + ASN1Type::CharacterString(CharacterString { ty, .. }) => string_type(ty), + ASN1Type::Enumerated(_) => Err(error!( + NotYetInplemented, + "Enumerated values are currently unsupported!" + )), + ASN1Type::Choice(_) => Err(error!( + NotYetInplemented, + "Choice values are currently unsupported!" + )), + ASN1Type::Sequence(_) => Err(error!( + NotYetInplemented, + "Sequence values are currently unsupported!" + )), + ASN1Type::SetOf(so) | ASN1Type::SequenceOf(so) => { + let _inner = type_to_tokens(&so.element_type)?; + Ok("SequenceOf".into()) + } + ASN1Type::ObjectIdentifier(_) => Err(error!( + NotYetInplemented, + "Object Identifier values are currently unsupported!" + )), + ASN1Type::Set(_) => Err(error!( + NotYetInplemented, + "Set values are currently unsupported!" + )), + ASN1Type::ElsewhereDeclaredType(e) => Ok(e.identifier.clone()), + ASN1Type::InformationObjectFieldReference(_) => Err(error!( + NotYetInplemented, + "Information Object field reference values are currently unsupported!" + )), + ASN1Type::Time(_) => Err(error!( + NotYetInplemented, + "Time values are currently unsupported!" + )), + ASN1Type::GeneralizedTime(_) => Ok("GeneralizedTime".into()), + ASN1Type::UTCTime(_) => Ok("UtcTime".into()), + ASN1Type::EmbeddedPdv | ASN1Type::External => Ok("Any".into()), + ASN1Type::ChoiceSelectionType(c) => { + let _choice = &c.choice_name; + let _option = &c.selected_option; + todo!() + } + } +} + +pub fn value_to_tokens( + value: &ASN1Value, + type_name: Option<&String>, +) -> Result { + match value { + ASN1Value::All => Err(error!( + NotYetInplemented, + "All values are currently unsupported!" + )), + ASN1Value::Null => todo!(), + ASN1Value::Choice { inner_value, .. } => { + if let Some(_) = type_name { + todo!() + } else { + Err(error!( + Unidentified, + "A type name is needed to stringify choice value {:?}", inner_value + )) + } + } + ASN1Value::OctetString(o) => { + let _bytes = o.iter().map(|byte| *byte); + todo!() + } + ASN1Value::SequenceOrSet(_) => Err(error!( + Unidentified, + "Unexpectedly encountered unlinked struct-like ASN1 value!" + )), + ASN1Value::LinkedStructLikeValue(fields) => { + if let Some(_ty_n) = type_name { + let _tokenized_fields = fields + .iter() + .map(|(_, _, val)| value_to_tokens(val.value(), None)) + .collect::, _>>()?; + todo!() + } else { + Err(error!( + Unidentified, + "A type name is needed to stringify sequence value {:?}", value + )) + } + } + ASN1Value::Boolean(b) => Ok(b.to_string()), + ASN1Value::Integer(i) => Ok(i.to_string()), + ASN1Value::String(s) => Ok(s.to_string()), + ASN1Value::Real(r) => Ok(r.to_string()), + ASN1Value::BitString(b) => { + let _bits = b.iter().map(|bit| bit.to_string()); + todo!() + } + ASN1Value::EnumeratedValue { + enumerated, + enumerable, + } => Ok(format!("{}_{}", enumerated, enumerable)), + ASN1Value::LinkedElsewhereDefinedValue { identifier: e, .. } + | ASN1Value::ElsewhereDeclaredValue { identifier: e, .. } => Ok(e.to_string()), + ASN1Value::ObjectIdentifier(oid) => { + let _arcs = oid + .0 + .iter() + .filter_map(|arc| arc.number.map(|id| id.to_string())); + todo!() + } + ASN1Value::Time(_t) => match type_name { + Some(_time_type) => todo!(), + None => todo!(), + }, + ASN1Value::LinkedArrayLikeValue(seq) => { + let _elems = seq + .iter() + .map(|v| value_to_tokens(v, None)) + .collect::, _>>()?; + todo!() + } + ASN1Value::LinkedNestedValue { + supertypes: _, + value, + } => Ok(value_to_tokens(value, type_name)?), + ASN1Value::LinkedIntValue { + integer_type, + value, + } => { + let val = *value; + match integer_type { + IntegerType::Unbounded => Ok(val.to_string()), + _ => Ok(val.to_string()), + } + } + ASN1Value::LinkedCharStringValue(string_type, value) => { + let _val = value; + match string_type { + CharacterStringType::NumericString => { + todo!() + } + CharacterStringType::VisibleString => { + todo!() + } + CharacterStringType::IA5String => { + todo!() + } + CharacterStringType::UTF8String => todo!(), + CharacterStringType::BMPString => { + todo!() + } + CharacterStringType::PrintableString => { + todo!() + } + CharacterStringType::GeneralString => { + todo!() + } + CharacterStringType::VideotexString + | CharacterStringType::GraphicString + | CharacterStringType::UniversalString + | CharacterStringType::TeletexString => Err(GeneratorError::new( + None, + &format!("{:?} values are currently unsupported!", string_type), + GeneratorErrorType::NotYetInplemented, + )), + } + } + } +} + +pub fn format_nested_sequence_members( + sequence_or_set: &SequenceOrSet, + parent_name: &String, +) -> Result, GeneratorError> { + sequence_or_set + .members + .iter() + .filter(|m| needs_unnesting(&m.ty)) + .map(|m| { + generate(ToplevelDefinition::Type(ToplevelTypeDefinition { + parameterization: None, + comments: " Inner type ".into(), + name: inner_name(&m.name, parent_name).to_string(), + ty: m.ty.clone(), + tag: None, + index: None, + })) + }) + .collect::, _>>() +} + +fn needs_unnesting(ty: &ASN1Type) -> bool { + match ty { + ASN1Type::Enumerated(_) + | ASN1Type::Choice(_) + | ASN1Type::Sequence(_) + | ASN1Type::Set(_) => true, + ASN1Type::SequenceOf(SequenceOrSetOf { element_type, .. }) + | ASN1Type::SetOf(SequenceOrSetOf { element_type, .. }) => needs_unnesting(element_type), + _ => false, + } +} + +pub fn format_nested_choice_options( + choice: &Choice, + parent_name: &String, +) -> Result, GeneratorError> { + choice + .options + .iter() + .filter(|m| { + matches!( + m.ty, + ASN1Type::Enumerated(_) + | ASN1Type::Choice(_) + | ASN1Type::Sequence(_) + | ASN1Type::SequenceOf(_) + | ASN1Type::Set(_) + ) + }) + .map(|m| { + generate(ToplevelDefinition::Type(ToplevelTypeDefinition { + parameterization: None, + comments: " Inner type ".into(), + name: inner_name(&m.name, parent_name).to_string(), + ty: m.ty.clone(), + tag: None, + index: None, + })) + }) + .collect::, _>>() +} + +pub fn format_sequence_or_set_of_item_type( + type_name: String, + first_item: Option<&ASN1Value>, +) -> String { + match type_name { + name if name == NULL => todo!(), + name if name == BOOLEAN => "bool".into(), + name if name == INTEGER => { + match first_item { + Some(ASN1Value::LinkedIntValue { integer_type, .. }) => { + integer_type.to_str().into() + } + _ => "int64".into(), // best effort + } + } + name if name == BIT_STRING => "BitString".into(), + name if name == OCTET_STRING => "OctetString".into(), + name if name == GENERALIZED_TIME => "GeneralizedTime".into(), + name if name == UTC_TIME => "UtcTime".into(), + name if name == OBJECT_IDENTIFIER => "ObjectIdentifier".into(), + name if name == NUMERIC_STRING => "NumericString".into(), + name if name == VISIBLE_STRING => "VisibleString".into(), + name if name == IA5_STRING => "IA5String".into(), + name if name == UTF8_STRING => "UTF8String".into(), + name if name == BMP_STRING => "BMPString".into(), + name if name == PRINTABLE_STRING => "PrintableString".into(), + name if name == GENERAL_STRING => "GeneralString".into(), + name => name, + } +} + +/// Resolves the custom syntax declared in an information object class' WITH SYNTAX clause +pub fn resolve_standard_syntax( + class: &InformationObjectClass, + application: &[InformationObjectField], +) -> Result<(ASN1Value, Vec<(usize, ASN1Type)>), GeneratorError> { + let mut key = None; + let mut field_index_map = Vec::<(usize, ASN1Type)>::new(); + + let key_index = class + .fields + .iter() + .enumerate() + .find_map(|(i, f)| f.is_unique.then_some(i)) + .ok_or_else(|| GeneratorError { + details: format!("Could not find key for class {class:?}"), + kind: GeneratorErrorType::MissingClassKey, + ..Default::default() + })?; + + let mut appl_iter = application.iter().enumerate(); + 'syntax_matching: for class_field in &class.fields { + if let Some((index, field)) = appl_iter.next() { + if class_field.identifier.identifier() == field.identifier() { + match field { + InformationObjectField::TypeField(f) => { + field_index_map.push((index, f.ty.clone())); + } + InformationObjectField::FixedValueField(f) => { + if index == key_index { + key = Some(f.value.clone()); + } + } + InformationObjectField::ObjectSetField(_) => todo!(), + } + } else if !class_field.is_optional { + return Err(GeneratorError { + top_level_declaration: None, + details: "Syntax mismatch while resolving information object.".to_string(), + kind: GeneratorErrorType::SyntaxMismatch, + }); + } else { + continue 'syntax_matching; + } + } + } + field_index_map.sort_by(|&(a, _), &(b, _)| a.cmp(&b)); + let types = field_index_map.into_iter().collect(); + match key { + Some(k) => Ok((k, types)), + None => Err(GeneratorError { + top_level_declaration: None, + details: "Could not find class key!".into(), + kind: GeneratorErrorType::MissingClassKey, + }), + } +} + +trait ASN1ValueExt { + fn is_const_type(&self) -> bool; +} + +impl ASN1ValueExt for ASN1Value { + fn is_const_type(&self) -> bool { + match self { + ASN1Value::Null | ASN1Value::Boolean(_) | ASN1Value::EnumeratedValue { .. } => true, + ASN1Value::Choice { inner_value, .. } => inner_value.is_const_type(), + ASN1Value::LinkedIntValue { integer_type, .. } => { + integer_type != &IntegerType::Unbounded + } + ASN1Value::LinkedNestedValue { value, .. } => value.is_const_type(), + ASN1Value::LinkedElsewhereDefinedValue { can_be_const, .. } => *can_be_const, + _ => false, + } + } +} + +impl ASN1ValueExt for ASN1Type { + fn is_const_type(&self) -> bool { + match self { + ASN1Type::Null | ASN1Type::Enumerated(_) | ASN1Type::Boolean(_) => true, + ASN1Type::Integer(i) => { + i.constraints.iter().fold(IntegerType::Unbounded, |acc, c| { + acc.max_restrictive(c.integer_constraints()) + }) != IntegerType::Unbounded + } + ASN1Type::Choice(c) => c + .options + .iter() + .fold(true, |acc, opt| opt.ty.is_const_type() && acc), + ASN1Type::Set(s) | ASN1Type::Sequence(s) => s + .members + .iter() + .fold(true, |acc, m| m.ty.is_const_type() && acc), + ASN1Type::SetOf(s) | ASN1Type::SequenceOf(s) => s.element_type.is_const_type(), + _ => false, + } + } +} diff --git a/utils/codegen/docker/rgen/tests/conversion.rs b/utils/codegen/docker/rgen/tests/conversion.rs new file mode 100644 index 000000000..992c2ccc6 --- /dev/null +++ b/utils/codegen/docker/rgen/tests/conversion.rs @@ -0,0 +1,136 @@ +mod utils; + +e2e_hs!( + single_byte, + r#" SingleByte ::= INTEGER (0..255)"#, + r#" +#pragma once +#include + +#include +#include +#include +#ifdef ROS1 +#include +namespace test_msgs = etsi_its_test_msgs; +#else +#include +namespace test_msgs = etsi_its_test_msgs::msg; +#endif + +namespace etsi_its_test_conversion { + +void toRos_SingleByte(const SingleByte_t& in, test_msgs::SingleByte& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); +} + +void toStruct_SingleByte(const test_msgs::SingleByte& in, SingleByte_t& out) { + memset(&out, 0, sizeof(SingleByte_t)); + + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); +} + +}"# +); + +e2e_hs!( + integer_unconstrained, + r#" Unbound ::= INTEGER "#, + r#" +#pragma once +#include + +#include +#include +#include +#ifdef ROS1 +#include +namespace test_msgs = etsi_its_test_msgs; +#else +#include +namespace test_msgs = etsi_its_test_msgs::msg; +#endif + +namespace etsi_its_test_conversion { + +void toRos_Unbound(const Unbound_t& in, test_msgs::Unbound& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); +} + +void toStruct_Unbound(const test_msgs::Unbound& in, Unbound_t& out) { + memset(&out, 0, sizeof(Unbound_t)); + + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); +} + +}"# +); + +e2e_hs!( + sequence, + r#" Seq ::= SEQUENCE { aBigNumber INTEGER, anotherBigNumber INTEGER} "#, + r#" +#pragma once +#include + +#include +#include +#include +#include +#include +#ifdef ROS1 +#include +namespace test_msgs = etsi_its_test_msgs; +#else +#include +namespace test_msgs = etsi_its_test_msgs::msg; +#endif + +namespace etsi_its_test_conversion { + +void toRos_Seq(const Seq_t& in, test_msgs::Seq& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in.aBigNumber, out.a_big_number); + etsi_its_primitives_conversion::toRos_INTEGER(in.anotherBigNumber, out.another_big_number); +} + +void toStruct_Seq(const test_msgs::Seq& in, Seq_t& out) { + memset(&out, 0, sizeof(Seq_t)); + + etsi_its_primitives_conversion::toStruct_INTEGER(in.a_big_number, out.aBigNumber); + etsi_its_primitives_conversion::toStruct_INTEGER(in.another_big_number, out.anotherBigNumber); +} + +}"# +); + +e2e_hs!(boolean, + r#" Maybe ::= BOOLEAN "#, + r#" +#pragma once +#include + +#include +#include +#include +#ifdef ROS1 +#include +namespace test_msgs = etsi_its_test_msgs; +#else +#include +namespace test_msgs = etsi_its_test_msgs::msg; +#endif + +namespace etsi_its_test_conversion { + +void toRos_Maybe(const Maybe_t& in, test_msgs::Maybe& out) { + etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value); +} + +void toStruct_Maybe(const test_msgs::Maybe& in, Maybe_t& out) { + memset(&out, 0, sizeof(Maybe_t)); + + etsi_its_primitives_conversion::toStruct_BOOLEAN(in.value, out); +} + +}"# +); diff --git a/utils/codegen/docker/rgen/tests/msgs.rs b/utils/codegen/docker/rgen/tests/msgs.rs new file mode 100644 index 000000000..b6863db2b --- /dev/null +++ b/utils/codegen/docker/rgen/tests/msgs.rs @@ -0,0 +1,50 @@ +mod utils; + +e2e_msgs!( + single_byte, + r#" SingleByte ::= INTEGER (0..255)"#, + r#" uint8 value + uint8 VALUE_MIN = 0 + uint8 VALUE_MAX = 255 "# +); + +e2e_msgs!( + integer_unconstrained, + r#" Unbound ::= INTEGER "#, + r#" int64 value "# +); + +e2e_msgs!( + integer_constrained_positive, + r#" PositiveNumber ::= INTEGER (0..MAX) "#, + r#" int64 value + int64 VALUE_MIN = 0 "# +); + +e2e_msgs!( + integer_constrained_negative, + r#" NegativeNumber ::= INTEGER (MIN..-1) "#, + r#" int64 value + int64 VALUE_MAX = -1 "# +); + +e2e_msgs!( + sequence, + r#" Seq ::= SEQUENCE { aBigNumber INTEGER, anotherBigNumber INTEGER} "#, + r#" int64 a_big_number + int64 another_big_number "# +); + +e2e_msgs!(boolean, r#" Maybe ::= BOOLEAN "#, r#" bool value "#); + +e2e_msgs!( + choice, + r#" Choose ::= CHOICE {aNumber INTEGER, aByteString OCTET STRING}"#, + r#" uint8 choice + + int64 a_number + uint8[] a_byte_string + + uint8 CHOICE_A_NUMBER = 0 + uint8 CHOICE_A_BYTE_STRING = 1"# +); diff --git a/utils/codegen/docker/rgen/tests/utils.rs b/utils/codegen/docker/rgen/tests/utils.rs new file mode 100644 index 000000000..9b0849ad0 --- /dev/null +++ b/utils/codegen/docker/rgen/tests/utils.rs @@ -0,0 +1,61 @@ +#[macro_export] +macro_rules! e2e_msgs { + ($suite:ident, $asn1:literal, $expected:literal) => { + #[test] + fn $suite() { + assert_eq!( + rasn_compiler::Compiler::new() + .with_backend(ros_backend::msgs::Msgs) + .add_asn_literal(&format!( + "TestModule DEFINITIONS AUTOMATIC TAGS::= BEGIN {} END", + $asn1 + )) + .compile_to_string() + .unwrap() + .generated + .replace("\n", "") + .replace("\n", "") + .lines() + .skip(1) + .collect::>() + .join("\n") + .replace(|c: char| c.is_whitespace(), ""), + format!("{}", $expected) + .to_string() + .replace(|c: char| c.is_whitespace(), ""), + ) + } + }; +} + +#[macro_export] +macro_rules! e2e_hs { + ($suite:ident, $asn1:literal, $expected:literal) => { + #[test] + fn $suite() { + assert_eq!( + rasn_compiler::Compiler::new() + .with_backend( + ros_backend::conversion::Conversion::default().set_main_pdu_name("test") + ) + .add_asn_literal(&format!( + "TestModule DEFINITIONS AUTOMATIC TAGS::= BEGIN {} END", + $asn1 + )) + .compile_to_string() + .unwrap() + .generated + .replace("#\n", "") + .replace("\n#", "") + .lines() + .skip(1) + .collect::>() + .join("\n") + .replace(|c: char| c.is_whitespace(), ""), + format!("{}", $expected) + .to_string() + .replace(|c: char| c.is_whitespace(), ""), + ) + } + }; +} From ada1911881e9cd92040876e877d28f6997c5953a Mon Sep 17 00:00:00 2001 From: v0-e Date: Wed, 8 May 2024 18:47:42 +0100 Subject: [PATCH 02/22] rgen: SEQUENCE members with distinguished values, constraint prefix renaming --- utils/codegen/docker/rgen/src/msgs/utils.rs | 41 +++++++++++++-------- 1 file changed, 26 insertions(+), 15 deletions(-) diff --git a/utils/codegen/docker/rgen/src/msgs/utils.rs b/utils/codegen/docker/rgen/src/msgs/utils.rs index e3b659ac9..06a6a99f9 100644 --- a/utils/codegen/docker/rgen/src/msgs/utils.rs +++ b/utils/codegen/docker/rgen/src/msgs/utils.rs @@ -81,9 +81,9 @@ pub fn format_constraints( per_constraints.is_extensible(), ); let range_prefix = if per_constraints.is_size_constraint() { - "LENGTH" + "LENGTH_" } else { - "VALUE" + "" }; // handle default size constraints if per_constraints.is_size_constraint() @@ -101,42 +101,49 @@ pub fn format_constraints( ) { (Some(min), Some(max), true) if min == max => { format!( - "{range_type} {range_prefix}_MIN = {min}\n\ - {range_type} {range_prefix}_MAX = {max}" + "{range_type} {range_prefix}MIN = {min}\n\ + {range_type} {range_prefix}MAX = {max}" ) } (Some(min), Some(max), true) => { format!( - "{range_type} {range_prefix}_MIN = {min}\n\ - {range_type} {range_prefix}_MAX = {max}" + "{range_type} {range_prefix}MIN = {min}\n\ + {range_type} {range_prefix}MAX = {max}" ) } (Some(min), Some(max), false) if min == max => { - format!("{range_type} {range_prefix} = {min}") + format!("{range_type} {range_prefix} = {min}", range_prefix = range_prefix.replace("_","")) } (Some(min), Some(max), false) => { format!( - "{range_type} {range_prefix}_MIN = {min}\n\ - {range_type} {range_prefix}_MAX = {max}" + "{range_type} {range_prefix}MIN = {min}\n\ + {range_type} {range_prefix}MAX = {max}" ) } (Some(min), None, true) => { - format!("{range_type} {range_prefix}_MIN = {min}") + format!("{range_type} {range_prefix}MIN = {min}") } (Some(min), None, false) => { - format!("{range_type} {range_prefix}_MIN = {min}") + format!("{range_type} {range_prefix}MIN = {min}") } (None, Some(max), true) => { - format!("{range_type} {range_prefix}_MAX = {max}") + format!("{range_type} {range_prefix}MAX = {max}") } (None, Some(max), false) => { - format!("{range_type} {range_prefix}_MAX = {max}") + format!("{range_type} {range_prefix}MAX = {max}") } _ => "".into(), }, ) } +pub fn get_distinguished_values(ty: &ASN1Type) -> Option> { + match ty { + ASN1Type::Integer(i) => i.distinguished_values.clone(), + _ => None, + } +} + pub fn format_distinguished_values(dvalues: &Option>) -> String { let mut result = String::from(""); if let Some(dvalues) = dvalues { @@ -243,16 +250,20 @@ fn format_sequence_member( let (mut all_constraints, mut formatted_type_name) = constraints_and_type_name(&member.ty, &member.name, parent_name)?; all_constraints.append(&mut member.constraints.clone()); + let distinguished_values = format_distinguished_values(&get_distinguished_values(&member.ty)) + .replace("{prefix}", &(to_ros_const_case(name).to_string() + &"_")) + .replace("{type}", &formatted_type_name); let name = to_ros_snake_case(name); if (member.is_optional && member.default_value.is_none()) || member.name.starts_with("ext_group_") { formatted_type_name = format!( "bool {name}_is_present\n\ - {formatted_type_name}" + {formatted_type_name}" ) } - Ok(format!("{formatted_type_name} {name}\n")) + Ok(format!("{formatted_type_name} {name}\n\ + {distinguished_values}\n")) } pub fn format_choice_options( From 878834366a40b27b53990f82b534360c4a3ab471 Mon Sep 17 00:00:00 2001 From: v0-e Date: Wed, 8 May 2024 19:15:49 +0100 Subject: [PATCH 03/22] rgen: SEQUENCE members with constraints --- utils/codegen/docker/rgen/src/msgs/builder.rs | 13 ++++++---- utils/codegen/docker/rgen/src/msgs/utils.rs | 25 +++++++++++-------- 2 files changed, 22 insertions(+), 16 deletions(-) diff --git a/utils/codegen/docker/rgen/src/msgs/builder.rs b/utils/codegen/docker/rgen/src/msgs/builder.rs index b5029596d..355008795 100644 --- a/utils/codegen/docker/rgen/src/msgs/builder.rs +++ b/utils/codegen/docker/rgen/src/msgs/builder.rs @@ -22,8 +22,8 @@ impl Backend for Msgs { s.len().gt(&0).then(|| { acc.0.push(format!( "\n\ - {s}\n\ - " + {s}\n\ + " )) }); acc @@ -153,7 +153,8 @@ pub fn generate_integer(tld: ToplevelTypeDefinition) -> Result Result Result d.identifier.clone(), _ => format!("Anonymous{}", &tld.name), }; - let constraints = format_constraints(true, &seq_or_set_of.constraints)?; + let constraints = format_constraints(true, &seq_or_set_of.constraints)? + .replace("{prefix}", ""); Ok(sequence_or_set_of_template( is_set_of, &format_comments(&tld.comments)?, diff --git a/utils/codegen/docker/rgen/src/msgs/utils.rs b/utils/codegen/docker/rgen/src/msgs/utils.rs index 06a6a99f9..cf0865cf9 100644 --- a/utils/codegen/docker/rgen/src/msgs/utils.rs +++ b/utils/codegen/docker/rgen/src/msgs/utils.rs @@ -101,36 +101,36 @@ pub fn format_constraints( ) { (Some(min), Some(max), true) if min == max => { format!( - "{range_type} {range_prefix}MIN = {min}\n\ - {range_type} {range_prefix}MAX = {max}" + "{range_type} {{prefix}}{range_prefix}MIN = {min}\n\ + {range_type} {{prefix}}{range_prefix}MAX = {max}" ) } (Some(min), Some(max), true) => { format!( - "{range_type} {range_prefix}MIN = {min}\n\ - {range_type} {range_prefix}MAX = {max}" + "{range_type} {{prefix}}{range_prefix}MIN = {min}\n\ + {range_type} {{prefix}}{range_prefix}MAX = {max}" ) } (Some(min), Some(max), false) if min == max => { - format!("{range_type} {range_prefix} = {min}", range_prefix = range_prefix.replace("_","")) + format!("{range_type} {{prefix}}{range_prefix} = {min}", range_prefix = range_prefix.replace("_","")) } (Some(min), Some(max), false) => { format!( - "{range_type} {range_prefix}MIN = {min}\n\ - {range_type} {range_prefix}MAX = {max}" + "{range_type} {{prefix}}{range_prefix}MIN = {min}\n\ + {range_type} {{prefix}}{range_prefix}MAX = {max}" ) } (Some(min), None, true) => { - format!("{range_type} {range_prefix}MIN = {min}") + format!("{range_type} {{prefix}}{range_prefix}MIN = {min}") } (Some(min), None, false) => { - format!("{range_type} {range_prefix}MIN = {min}") + format!("{range_type} {{prefix}}{range_prefix}MIN = {min}") } (None, Some(max), true) => { - format!("{range_type} {range_prefix}MAX = {max}") + format!("{range_type} {{prefix}}{range_prefix}MAX = {max}") } (None, Some(max), false) => { - format!("{range_type} {range_prefix}MAX = {max}") + format!("{range_type} {{prefix}}{range_prefix}MAX = {max}") } _ => "".into(), }, @@ -250,6 +250,8 @@ fn format_sequence_member( let (mut all_constraints, mut formatted_type_name) = constraints_and_type_name(&member.ty, &member.name, parent_name)?; all_constraints.append(&mut member.constraints.clone()); + let formatted_constraints = format_constraints(false, &all_constraints)? + .replace("{prefix}", &(to_ros_const_case(name).to_string() + &"_")); let distinguished_values = format_distinguished_values(&get_distinguished_values(&member.ty)) .replace("{prefix}", &(to_ros_const_case(name).to_string() + &"_")) .replace("{type}", &formatted_type_name); @@ -263,6 +265,7 @@ fn format_sequence_member( ) } Ok(format!("{formatted_type_name} {name}\n\ + {formatted_constraints}\n\ {distinguished_values}\n")) } From d0a07399eb87df1a4c275894dd6d0605e6125b20 Mon Sep 17 00:00:00 2001 From: v0-e Date: Wed, 8 May 2024 19:28:25 +0100 Subject: [PATCH 04/22] rgen: BIT STRING constraint LENGTH -> SIZE_BITS --- utils/codegen/docker/rgen/src/msgs/builder.rs | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/utils/codegen/docker/rgen/src/msgs/builder.rs b/utils/codegen/docker/rgen/src/msgs/builder.rs index 355008795..836433284 100644 --- a/utils/codegen/docker/rgen/src/msgs/builder.rs +++ b/utils/codegen/docker/rgen/src/msgs/builder.rs @@ -173,7 +173,8 @@ pub fn generate_bit_string(tld: ToplevelTypeDefinition) -> Result", + "#include ", pdu = pdu, ros_fn = to_ros_title_case(name) ); From 5658bdd3bd99d49c423f0d1a6854d72ce0ce8f24 Mon Sep 17 00:00:00 2001 From: v0-e Date: Thu, 16 May 2024 12:23:22 +0100 Subject: [PATCH 06/22] rgen: conversion hyphened c-filename/type fix --- utils/codegen/docker/rgen/src/common/mod.rs | 9 +++++++++ utils/codegen/docker/rgen/src/conversion/builder.rs | 4 ++-- utils/codegen/docker/rgen/src/conversion/template.rs | 11 ++++++----- 3 files changed, 17 insertions(+), 7 deletions(-) diff --git a/utils/codegen/docker/rgen/src/common/mod.rs b/utils/codegen/docker/rgen/src/common/mod.rs index 5218c1440..913897a44 100644 --- a/utils/codegen/docker/rgen/src/common/mod.rs +++ b/utils/codegen/docker/rgen/src/common/mod.rs @@ -58,3 +58,12 @@ pub fn to_ros_title_case(input: &str) -> String { input.to_string() } } + +pub fn to_c_title_case(input: &str) -> String { + let input = input.replace('-', "_"); + match input.as_str() { + "long" => "Long".to_string(), + "class" => "Class".to_string(), + _ => input + } +} diff --git a/utils/codegen/docker/rgen/src/conversion/builder.rs b/utils/codegen/docker/rgen/src/conversion/builder.rs index d0c5ffa50..8a5e1a7c8 100644 --- a/utils/codegen/docker/rgen/src/conversion/builder.rs +++ b/utils/codegen/docker/rgen/src/conversion/builder.rs @@ -2,7 +2,7 @@ use std::error::Error; use rasn_compiler::prelude::{ir::*, *}; -use crate::common::{to_ros_const_case, to_ros_title_case, IntegerTypeExt}; +use crate::common::{to_ros_const_case, IntegerTypeExt}; use crate::conversion::{generate, Conversion, ConversionOptions}; use crate::conversion::{template::*, utils::*}; @@ -194,7 +194,7 @@ pub fn generate_integer( Ok(integer_template( &options, &format_comments(&tld.comments)?, - &to_ros_title_case(&tld.name), + &tld.name, )) } else { Err(GeneratorError::new( diff --git a/utils/codegen/docker/rgen/src/conversion/template.rs b/utils/codegen/docker/rgen/src/conversion/template.rs index 63093b021..d96f016ab 100644 --- a/utils/codegen/docker/rgen/src/conversion/template.rs +++ b/utils/codegen/docker/rgen/src/conversion/template.rs @@ -1,4 +1,4 @@ -use crate::common::{to_ros_const_case, to_ros_snake_case, to_ros_title_case}; +use crate::common::{to_ros_const_case, to_ros_snake_case, to_ros_title_case, to_c_title_case}; use crate::conversion::utils::{InnerTypes, NameType, NamedSeqMember}; use crate::conversion::ConversionOptions; @@ -11,7 +11,7 @@ const CONVERSION_TEMPLATE: &str = r#"//// {asn1_type} {name} #include -#include +#include {c_includes} #ifdef ROS1 {ros1_includes} @@ -85,9 +85,10 @@ pub fn conversion_template( .replace("{ros1_includes}", &ros1_includes) .replace("{ros2_includes}", &ros2_includes) .replace("{asn1_type}", asn1_type) - .replace("{name}", name) - .replace("{c_type}", name) - .replace("{type}", name) + .replace("{name}", &to_ros_title_case(name)) + .replace("{c_type}", &to_c_title_case(name)) + .replace("{c_filename}", name) + .replace("{type}", &to_ros_title_case(name)) .replace("{ros_type}", &to_ros_title_case(name)) .replace("{pdu}", pdu) .replace("{to_ros_members}", &to_ros_members) From 5a871fd9ed345fbe0122ae650d7c9ba73d271cd9 Mon Sep 17 00:00:00 2001 From: v0-e Date: Thu, 16 May 2024 12:42:53 +0100 Subject: [PATCH 07/22] rgen: Util scripts -m -> -t, remove need for -m in .msgs gen --- utils/codegen/asn1ToConversionHeader-rgen.py | 2 +- utils/codegen/asn1ToRosMsg-rgen.py | 3 +-- utils/codegen/docker/rgen.Dockerfile | 2 +- utils/codegen/docker/rgen/README.md | 4 ++-- utils/codegen/docker/rgen/src/msgs/bin.rs | 5 ----- 5 files changed, 5 insertions(+), 11 deletions(-) diff --git a/utils/codegen/asn1ToConversionHeader-rgen.py b/utils/codegen/asn1ToConversionHeader-rgen.py index 73654ed31..a1ca15d65 100755 --- a/utils/codegen/asn1ToConversionHeader-rgen.py +++ b/utils/codegen/asn1ToConversionHeader-rgen.py @@ -46,7 +46,7 @@ def parseCli(): parser.add_argument("files", type=str, nargs="+", help="ASN1 files") parser.add_argument("-o", "--output-dir", type=str, required=True, help="output directory") parser.add_argument("-td", "--temp-dir", type=str, default=None, help="temporary directory for mounting files to container; uses tempfile by default") - parser.add_argument("-m", "--message", type=str, required=True, help="message name") + parser.add_argument("-t", "--message", type=str, required=True, help="message name") parser.add_argument("-di", "--docker-image", type=str, default="ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen", help="rgen Docker image") args = parser.parse_args() diff --git a/utils/codegen/asn1ToRosMsg-rgen.py b/utils/codegen/asn1ToRosMsg-rgen.py index 14f19ea2b..102fe44fe 100755 --- a/utils/codegen/asn1ToRosMsg-rgen.py +++ b/utils/codegen/asn1ToRosMsg-rgen.py @@ -46,7 +46,6 @@ def parseCli(): parser.add_argument("files", type=str, nargs="+", help="ASN1 files") parser.add_argument("-o", "--output-dir", type=str, required=True, help="output directory") parser.add_argument("-td", "--temp-dir", type=str, default=None, help="temporary directory for mounting files to container; uses tempfile by default") - parser.add_argument("-m", "--message", type=str, required=True, help="message name") parser.add_argument("-di", "--docker-image", type=str, default="ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen", help="rgen Docker image") args = parser.parse_args() @@ -78,7 +77,7 @@ def main(): shutil.copy(f, container_input_dir) # run asn1c docker container to generate header and source files - subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'msgs', args.message], check=True) + subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'msgs', ""], check=True) # move generated header and source files to output directories for f in glob.glob(os.path.join(container_output_dir, "*.msg")): diff --git a/utils/codegen/docker/rgen.Dockerfile b/utils/codegen/docker/rgen.Dockerfile index 04b62b48d..c6f335b2a 100644 --- a/utils/codegen/docker/rgen.Dockerfile +++ b/utils/codegen/docker/rgen.Dockerfile @@ -39,7 +39,7 @@ generator=\$1\n\ pdu=\$2\n\ case \$generator in\n\ 'msgs')\n\ - asn1-to-ros-msgs -o . -p \$pdu \$(find /input -name '*.asn')\n\ + asn1-to-ros-msgs -o . \$(find /input -name '*.asn')\n\ ;;\n\ 'conversion-headers')\n\ asn1-to-ros-conversion-headers -o . -p \$pdu \$(find /input -name '*.asn')\n\ diff --git a/utils/codegen/docker/rgen/README.md b/utils/codegen/docker/rgen/README.md index 71c7fea6d..fd3aeb137 100644 --- a/utils/codegen/docker/rgen/README.md +++ b/utils/codegen/docker/rgen/README.md @@ -4,8 +4,8 @@ Backends for the rasn compiler, which converts ASN.1 files to ROS message files, Support mainly for ETSI ITS messages. ## Usage -To generate the ROS `.msg`s run `cargo run --bin asn1-to-ros-msgs -- -p -o [ASN.1 files ...]`, where `` is the main PDU name used as a reference (e.g. `cam`, `denm`), and `` is the output directory. +To generate the ROS `.msg`s run `cargo run --bin asn1-to-ros-msgs -- -o [ASN.1 files ...]`, where `` is the output directory. -To generate the conversion headers run `cargo run --bin asn1-to-ros-conversion-headers -- -p -o [ASN.1 files ...]`. +To generate the conversion headers run `cargo run --bin asn1-to-ros-conversion-headers -- -p -o [ASN.1 files ...]`, where `` is the main PDU name used as a reference (e.g. `cam`, `denm`). The corresponding ROS `.msg`s and conversion headers will be generated in the `out` directory. diff --git a/utils/codegen/docker/rgen/src/msgs/bin.rs b/utils/codegen/docker/rgen/src/msgs/bin.rs index 9bacc5397..7eb64b1ed 100644 --- a/utils/codegen/docker/rgen/src/msgs/bin.rs +++ b/utils/codegen/docker/rgen/src/msgs/bin.rs @@ -1,5 +1,3 @@ -use std::path::PathBuf; - use clap::Parser; use regex::Regex; @@ -8,9 +6,6 @@ use ros_backend::msgs::Msgs; #[derive(Parser, Debug)] struct Cli { - /// Main PDU name - #[clap(short, long)] - pdu: String, #[clap(short, long)] /// Output directory out: std::path::PathBuf, From 0c68ed1a22f1e2b7a5a47d52c9d746356be2dd69 Mon Sep 17 00:00:00 2001 From: v0-e Date: Thu, 16 May 2024 13:45:28 +0100 Subject: [PATCH 08/22] CAM, DENM .msgs and conversion headers by rgen --- .../convertAccelerationConfidence.h | 32 +----- .../convertAccelerationControl.h | 32 +----- .../convertAccidentSubCauseCode.h | 32 +----- .../etsi_its_cam_conversion/convertActionID.h | 31 +----- ...erseWeatherConditionAdhesionSubCauseCode.h | 32 +----- ...itionExtremeWeatherConditionSubCauseCode.h | 32 +----- ...eatherConditionPrecipitationSubCauseCode.h | 32 +----- ...seWeatherConditionVisibilitySubCauseCode.h | 32 +----- .../etsi_its_cam_conversion/convertAltitude.h | 31 +----- .../convertAltitudeConfidence.h | 33 ++---- .../convertAltitudeValue.h | 32 +----- .../convertBasicContainer.h | 31 +----- ...onvertBasicVehicleContainerHighFrequency.h | 80 ++++---------- ...convertBasicVehicleContainerLowFrequency.h | 31 +----- .../etsi_its_cam_conversion/convertCAM.h | 32 +----- .../convertCamParameters.h | 45 ++------ .../convertCauseCode.h | 31 +----- .../convertCauseCodeType.h | 32 +----- .../convertCenDsrcTollingZone.h | 38 ++----- .../convertCenDsrcTollingZoneID.h | 33 ++---- .../convertClosedLanes.h | 52 ++------- .../convertCollisionRiskSubCauseCode.h | 32 +----- .../convertCoopAwareness.h | 31 +----- .../convertCurvature.h | 31 +----- .../convertCurvatureCalculationMode.h | 33 ++---- .../convertCurvatureConfidence.h | 33 ++---- .../convertCurvatureValue.h | 32 +----- .../convertDangerousEndOfQueueSubCauseCode.h | 32 +----- .../convertDangerousGoodsBasic.h | 33 ++---- .../convertDangerousGoodsContainer.h | 31 +----- .../convertDangerousGoodsExtended.h | 58 +++------- .../convertDangerousSituationSubCauseCode.h | 32 +----- .../convertDeltaAltitude.h | 32 +----- .../convertDeltaLatitude.h | 32 +----- .../convertDeltaLongitude.h | 32 +----- .../convertDeltaReferencePosition.h | 31 +----- .../convertDigitalMap.h | 54 ++-------- .../convertDriveDirection.h | 33 ++---- .../convertDrivingLaneStatus.h | 32 +----- .../convertEmbarkationStatus.h | 32 +----- .../convertEmergencyContainer.h | 45 ++------ .../convertEmergencyPriority.h | 32 +----- ...tEmergencyVehicleApproachingSubCauseCode.h | 32 +----- .../convertEnergyStorageType.h | 32 +----- .../convertEventHistory.h | 54 ++-------- .../convertEventPoint.h | 38 ++----- .../convertExteriorLights.h | 32 +----- .../convertGenerationDeltaTime.h | 32 +----- .../convertHardShoulderStatus.h | 33 ++---- ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 32 +----- ...ardousLocationDangerousCurveSubCauseCode.h | 32 +----- ...ousLocationObstacleOnTheRoadSubCauseCode.h | 32 +----- ...dousLocationSurfaceConditionSubCauseCode.h | 32 +----- .../etsi_its_cam_conversion/convertHeading.h | 31 +----- .../convertHeadingConfidence.h | 32 +----- .../convertHeadingValue.h | 32 +----- .../convertHeightLonCarr.h | 32 +----- .../convertHighFrequencyContainer.h | 52 +++------ ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 32 +----- .../convertHumanProblemSubCauseCode.h | 32 +----- .../convertInformationQuality.h | 32 +----- .../convertItineraryPath.h | 54 ++-------- .../convertItsPduHeader.h | 33 ++---- .../convertLanePosition.h | 32 +----- .../convertLateralAcceleration.h | 31 +----- .../convertLateralAccelerationValue.h | 32 +----- .../etsi_its_cam_conversion/convertLatitude.h | 32 +----- .../convertLightBarSirenInUse.h | 32 +----- .../convertLongitude.h | 32 +----- .../convertLongitudinalAcceleration.h | 31 +----- .../convertLongitudinalAccelerationValue.h | 32 +----- .../convertLowFrequencyContainer.h | 42 +++----- .../convertNumberOfOccupants.h | 32 +----- .../convertOpeningDaysHours.h | 32 +----- .../convertPathDeltaTime.h | 32 +----- .../convertPathHistory.h | 54 ++-------- .../convertPathPoint.h | 38 ++----- .../convertPerformanceClass.h | 32 +----- .../convertPhoneNumber.h | 32 +----- .../convertPosCentMass.h | 32 +----- .../convertPosConfidenceEllipse.h | 31 +----- .../convertPosFrontAx.h | 32 +----- .../convertPosLonCarr.h | 32 +----- .../convertPosPillar.h | 32 +----- .../convertPositionOfOccupants.h | 32 +----- .../convertPositionOfPillars.h | 54 ++-------- .../convertPositioningSolutionType.h | 33 ++---- .../convertPostCrashSubCauseCode.h | 32 +----- .../convertProtectedCommunicationZone.h | 52 ++------- .../convertProtectedCommunicationZonesRSU.h | 54 ++-------- .../convertProtectedZoneID.h | 32 +----- .../convertProtectedZoneRadius.h | 32 +----- .../convertProtectedZoneType.h | 33 ++---- .../convertPtActivation.h | 31 +----- .../convertPtActivationData.h | 32 +----- .../convertPtActivationType.h | 32 +----- .../convertPublicTransportContainer.h | 38 ++----- .../convertRSUContainerHighFrequency.h | 38 ++----- .../convertReferencePosition.h | 31 +----- .../convertRelevanceDistance.h | 33 ++---- .../convertRelevanceTrafficDirection.h | 33 ++---- .../convertRequestResponseIndication.h | 33 ++---- ...cueAndRecoveryWorkInProgressSubCauseCode.h | 32 +----- .../convertRescueContainer.h | 31 +----- .../convertRestrictedTypes.h | 54 ++-------- .../etsi_its_cam_conversion/convertRoadType.h | 33 ++---- .../convertRoadWorksContainerBasic.h | 45 ++------ .../convertRoadworksSubCauseCode.h | 32 +----- .../convertSafetyCarContainer.h | 52 ++------- .../convertSemiAxisLength.h | 32 +----- .../convertSequenceNumber.h | 32 +----- .../convertSignalViolationSubCauseCode.h | 32 +----- .../convertSlowVehicleSubCauseCode.h | 32 +----- .../convertSpecialTransportContainer.h | 31 +----- .../convertSpecialTransportType.h | 32 +----- .../convertSpecialVehicleContainer.h | 102 +++++++----------- .../etsi_its_cam_conversion/convertSpeed.h | 31 +----- .../convertSpeedConfidence.h | 32 +----- .../convertSpeedLimit.h | 32 +----- .../convertSpeedValue.h | 32 +----- .../convertStationID.h | 32 +----- .../convertStationType.h | 32 +----- .../convertStationarySince.h | 33 ++---- .../convertStationaryVehicleSubCauseCode.h | 32 +----- .../convertSteeringWheelAngle.h | 31 +----- .../convertSteeringWheelAngleConfidence.h | 32 +----- .../convertSteeringWheelAngleValue.h | 32 +----- .../convertSubCauseCodeType.h | 32 +----- .../convertTemperature.h | 32 +----- .../convertTimestampIts.h | 32 +----- .../etsi_its_cam_conversion/convertTraces.h | 54 ++-------- .../convertTrafficConditionSubCauseCode.h | 32 +----- .../convertTrafficRule.h | 33 ++---- .../convertTransmissionInterval.h | 32 +----- .../convertTurningRadius.h | 32 +----- .../etsi_its_cam_conversion/convertVDS.h | 32 +----- .../convertValidityDuration.h | 32 +----- .../convertVehicleBreakdownSubCauseCode.h | 32 +----- .../convertVehicleIdentification.h | 57 +++------- .../convertVehicleLength.h | 31 +----- ...convertVehicleLengthConfidenceIndication.h | 33 ++---- .../convertVehicleLengthValue.h | 32 +----- .../convertVehicleMass.h | 32 +----- .../convertVehicleRole.h | 33 ++---- .../convertVehicleWidth.h | 32 +----- .../convertVerticalAcceleration.h | 31 +----- .../convertVerticalAccelerationValue.h | 32 +----- .../convertWMInumber.h | 32 +----- .../convertWheelBaseVehicle.h | 32 +----- .../convertWrongWayDrivingSubCauseCode.h | 32 +----- .../etsi_its_cam_conversion/convertYawRate.h | 31 +----- .../convertYawRateConfidence.h | 33 ++---- .../convertYawRateValue.h | 32 +----- .../convertAccelerationConfidence.h | 32 +----- .../convertAccelerationControl.h | 32 +----- .../convertAccidentSubCauseCode.h | 32 +----- .../convertActionID.h | 31 +----- ...erseWeatherConditionAdhesionSubCauseCode.h | 32 +----- ...itionExtremeWeatherConditionSubCauseCode.h | 32 +----- ...eatherConditionPrecipitationSubCauseCode.h | 32 +----- ...seWeatherConditionVisibilitySubCauseCode.h | 32 +----- .../convertAlacarteContainer.h | 73 +++---------- .../convertAltitude.h | 31 +----- .../convertAltitudeConfidence.h | 33 ++---- .../convertAltitudeValue.h | 32 +----- .../convertCauseCode.h | 31 +----- .../convertCauseCodeType.h | 32 +----- .../convertCenDsrcTollingZone.h | 38 ++----- .../convertCenDsrcTollingZoneID.h | 33 ++---- .../convertClosedLanes.h | 52 ++------- .../convertCollisionRiskSubCauseCode.h | 32 +----- .../convertCurvature.h | 31 +----- .../convertCurvatureCalculationMode.h | 33 ++---- .../convertCurvatureConfidence.h | 33 ++---- .../convertCurvatureValue.h | 32 +----- .../etsi_its_denm_conversion/convertDENM.h | 31 +----- .../convertDangerousEndOfQueueSubCauseCode.h | 32 +----- .../convertDangerousGoodsBasic.h | 33 ++---- .../convertDangerousGoodsExtended.h | 58 +++------- .../convertDangerousSituationSubCauseCode.h | 32 +----- ...tralizedEnvironmentalNotificationMessage.h | 52 ++------- .../convertDeltaAltitude.h | 32 +----- .../convertDeltaLatitude.h | 32 +----- .../convertDeltaLongitude.h | 32 +----- .../convertDeltaReferencePosition.h | 31 +----- .../convertDigitalMap.h | 54 ++-------- .../convertDriveDirection.h | 33 ++---- .../convertDrivingLaneStatus.h | 32 +----- .../convertEmbarkationStatus.h | 32 +----- .../convertEmergencyPriority.h | 32 +----- ...tEmergencyVehicleApproachingSubCauseCode.h | 32 +----- .../convertEnergyStorageType.h | 32 +----- .../convertEventHistory.h | 54 ++-------- .../convertEventPoint.h | 38 ++----- .../convertExteriorLights.h | 32 +----- .../convertHardShoulderStatus.h | 33 ++---- ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 32 +----- ...ardousLocationDangerousCurveSubCauseCode.h | 32 +----- ...ousLocationObstacleOnTheRoadSubCauseCode.h | 32 +----- ...dousLocationSurfaceConditionSubCauseCode.h | 32 +----- .../etsi_its_denm_conversion/convertHeading.h | 31 +----- .../convertHeadingConfidence.h | 32 +----- .../convertHeadingValue.h | 32 +----- .../convertHeightLonCarr.h | 32 +----- ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 32 +----- .../convertHumanProblemSubCauseCode.h | 32 +----- .../convertImpactReductionContainer.h | 31 +----- .../convertInformationQuality.h | 32 +----- .../convertItineraryPath.h | 54 ++-------- .../convertItsPduHeader.h | 33 ++---- .../convertLanePosition.h | 32 +----- .../convertLateralAcceleration.h | 31 +----- .../convertLateralAccelerationValue.h | 32 +----- .../convertLatitude.h | 32 +----- .../convertLightBarSirenInUse.h | 32 +----- .../convertLocationContainer.h | 52 ++------- .../convertLongitude.h | 32 +----- .../convertLongitudinalAcceleration.h | 31 +----- .../convertLongitudinalAccelerationValue.h | 32 +----- .../convertManagementContainer.h | 66 +++--------- .../convertNumberOfOccupants.h | 32 +----- .../convertOpeningDaysHours.h | 32 +----- .../convertPathDeltaTime.h | 32 +----- .../convertPathHistory.h | 54 ++-------- .../convertPathPoint.h | 38 ++----- .../convertPerformanceClass.h | 32 +----- .../convertPhoneNumber.h | 32 +----- .../convertPosCentMass.h | 32 +----- .../convertPosConfidenceEllipse.h | 31 +----- .../convertPosFrontAx.h | 32 +----- .../convertPosLonCarr.h | 32 +----- .../convertPosPillar.h | 32 +----- .../convertPositionOfOccupants.h | 32 +----- .../convertPositionOfPillars.h | 54 ++-------- .../convertPositioningSolutionType.h | 33 ++---- .../convertPostCrashSubCauseCode.h | 32 +----- .../convertProtectedCommunicationZone.h | 52 ++------- .../convertProtectedCommunicationZonesRSU.h | 54 ++-------- .../convertProtectedZoneID.h | 32 +----- .../convertProtectedZoneRadius.h | 32 +----- .../convertProtectedZoneType.h | 33 ++---- .../convertPtActivation.h | 31 +----- .../convertPtActivationData.h | 32 +----- .../convertPtActivationType.h | 32 +----- .../convertReferenceDenms.h | 54 ++-------- .../convertReferencePosition.h | 31 +----- .../convertRelevanceDistance.h | 33 ++---- .../convertRelevanceTrafficDirection.h | 33 ++---- .../convertRequestResponseIndication.h | 33 ++---- ...cueAndRecoveryWorkInProgressSubCauseCode.h | 32 +----- .../convertRestrictedTypes.h | 54 ++-------- .../convertRoadType.h | 33 ++---- .../convertRoadWorksContainerExtended.h | 94 ++++------------ .../convertRoadworksSubCauseCode.h | 32 +----- .../convertSemiAxisLength.h | 32 +----- .../convertSequenceNumber.h | 32 +----- .../convertSignalViolationSubCauseCode.h | 32 +----- .../convertSituationContainer.h | 45 ++------ .../convertSlowVehicleSubCauseCode.h | 32 +----- .../convertSpecialTransportType.h | 32 +----- .../etsi_its_denm_conversion/convertSpeed.h | 31 +----- .../convertSpeedConfidence.h | 32 +----- .../convertSpeedLimit.h | 32 +----- .../convertSpeedValue.h | 32 +----- .../convertStationID.h | 32 +----- .../convertStationType.h | 32 +----- .../convertStationarySince.h | 33 ++---- .../convertStationaryVehicleContainer.h | 73 +++---------- .../convertStationaryVehicleSubCauseCode.h | 32 +----- .../convertSteeringWheelAngle.h | 31 +----- .../convertSteeringWheelAngleConfidence.h | 32 +----- .../convertSteeringWheelAngleValue.h | 32 +----- .../convertSubCauseCodeType.h | 32 +----- .../convertTemperature.h | 32 +----- .../convertTermination.h | 33 ++---- .../convertTimestampIts.h | 32 +----- .../etsi_its_denm_conversion/convertTraces.h | 54 ++-------- .../convertTrafficConditionSubCauseCode.h | 32 +----- .../convertTrafficRule.h | 33 ++---- .../convertTransmissionInterval.h | 32 +----- .../convertTurningRadius.h | 32 +----- .../etsi_its_denm_conversion/convertVDS.h | 32 +----- .../convertValidityDuration.h | 32 +----- .../convertVehicleBreakdownSubCauseCode.h | 32 +----- .../convertVehicleIdentification.h | 57 +++------- .../convertVehicleLength.h | 31 +----- ...convertVehicleLengthConfidenceIndication.h | 33 ++---- .../convertVehicleLengthValue.h | 32 +----- .../convertVehicleMass.h | 32 +----- .../convertVehicleRole.h | 33 ++---- .../convertVehicleWidth.h | 32 +----- .../convertVerticalAcceleration.h | 31 +----- .../convertVerticalAccelerationValue.h | 32 +----- .../convertWMInumber.h | 32 +----- .../convertWheelBaseVehicle.h | 32 +----- .../convertWrongWayDrivingSubCauseCode.h | 32 +----- .../etsi_its_denm_conversion/convertYawRate.h | 31 +----- .../convertYawRateConfidence.h | 33 ++---- .../convertYawRateValue.h | 32 +----- .../msg/AccelerationConfidence.msg | 33 +----- .../msg/AccelerationControl.msg | 40 +------ .../msg/AccidentSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/ActionID.msg | 39 ++----- ...seWeatherConditionAdhesionSubCauseCode.msg | 33 +----- ...ionExtremeWeatherConditionSubCauseCode.msg | 33 +----- ...therConditionPrecipitationSubCauseCode.msg | 33 +----- ...WeatherConditionVisibilitySubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/Altitude.msg | 39 ++----- .../msg/AltitudeConfidence.msg | 47 +------- .../etsi_its_cam_msgs/msg/AltitudeValue.msg | 33 +----- .../etsi_its_cam_msgs/msg/BasicContainer.msg | 40 ++----- .../BasicVehicleContainerHighFrequency.msg | 81 +++++--------- .../msg/BasicVehicleContainerLowFrequency.msg | 41 ++----- etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg | 40 ++----- .../etsi_its_cam_msgs/msg/CamParameters.msg | 48 ++------- .../etsi_its_cam_msgs/msg/CauseCode.msg | 40 ++----- .../etsi_its_cam_msgs/msg/CauseCodeType.msg | 61 +---------- .../msg/CenDsrcTollingZone.msg | 44 ++------ .../msg/CenDsrcTollingZoneID.msg | 31 +----- .../etsi_its_cam_msgs/msg/ClosedLanes.msg | 48 ++------- .../msg/CollisionRiskSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/CoopAwareness.msg | 39 ++----- .../etsi_its_cam_msgs/msg/Curvature.msg | 39 ++----- .../msg/CurvatureCalculationMode.msg | 30 +----- .../msg/CurvatureConfidence.msg | 39 +------ .../etsi_its_cam_msgs/msg/CurvatureValue.msg | 33 +----- .../msg/DangerousEndOfQueueSubCauseCode.msg | 33 +----- .../msg/DangerousGoodsBasic.msg | 63 ++--------- .../msg/DangerousGoodsContainer.msg | 35 +----- .../msg/DangerousGoodsExtended.msg | 63 +++-------- .../msg/DangerousSituationSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/DeltaAltitude.msg | 33 +----- .../etsi_its_cam_msgs/msg/DeltaLatitude.msg | 33 +----- .../etsi_its_cam_msgs/msg/DeltaLongitude.msg | 33 +----- .../msg/DeltaReferencePosition.msg | 41 ++----- .../etsi_its_cam_msgs/msg/DigitalMap.msg | 35 +----- .../etsi_its_cam_msgs/msg/DriveDirection.msg | 30 +----- .../msg/DrivingLaneStatus.msg | 34 +----- .../msg/EmbarkationStatus.msg | 31 +----- .../msg/EmergencyContainer.msg | 45 ++------ .../msg/EmergencyPriority.msg | 32 +----- ...mergencyVehicleApproachingSubCauseCode.msg | 33 +----- .../msg/EnergyStorageType.msg | 32 +----- .../etsi_its_cam_msgs/msg/EventHistory.msg | 35 +----- .../etsi_its_cam_msgs/msg/EventPoint.msg | 43 ++------ .../etsi_its_cam_msgs/msg/ExteriorLights.msg | 41 +------ .../msg/GenerationDeltaTime.msg | 33 +----- .../msg/HardShoulderStatus.msg | 30 +----- ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 33 +----- ...dousLocationDangerousCurveSubCauseCode.msg | 33 +----- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 33 +----- ...usLocationSurfaceConditionSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/Heading.msg | 39 ++----- .../msg/HeadingConfidence.msg | 33 +----- .../etsi_its_cam_msgs/msg/HeadingValue.msg | 41 ++----- .../etsi_its_cam_msgs/msg/HeightLonCarr.msg | 33 +----- .../msg/HighFrequencyContainer.msg | 39 +------ .../HumanPresenceOnTheRoadSubCauseCode.msg | 33 +----- .../msg/HumanProblemSubCauseCode.msg | 33 +----- .../msg/InformationQuality.msg | 33 +----- .../etsi_its_cam_msgs/msg/ItineraryPath.msg | 35 +----- .../etsi_its_cam_msgs/msg/ItsPduHeader.msg | 37 ++----- .../etsi_its_cam_msgs/msg/LanePosition.msg | 34 +----- .../msg/LateralAcceleration.msg | 39 ++----- .../msg/LateralAccelerationValue.msg | 33 +----- .../etsi_its_cam_msgs/msg/Latitude.msg | 33 +----- .../msg/LightBarSirenInUse.msg | 35 +----- .../etsi_its_cam_msgs/msg/Longitude.msg | 33 +----- .../msg/LongitudinalAcceleration.msg | 39 ++----- .../msg/LongitudinalAccelerationValue.msg | 33 +----- .../msg/LowFrequencyContainer.msg | 35 +----- .../msg/NumberOfOccupants.msg | 33 +----- .../msg/OpeningDaysHours.msg | 31 +----- .../etsi_its_cam_msgs/msg/PathDeltaTime.msg | 37 +------ .../etsi_its_cam_msgs/msg/PathHistory.msg | 35 +----- .../etsi_its_cam_msgs/msg/PathPoint.msg | 41 ++----- .../msg/PerformanceClass.msg | 33 +----- .../etsi_its_cam_msgs/msg/PhoneNumber.msg | 33 +----- .../etsi_its_cam_msgs/msg/PosCentMass.msg | 33 +----- .../msg/PosConfidenceEllipse.msg | 41 ++----- .../etsi_its_cam_msgs/msg/PosFrontAx.msg | 33 +----- .../etsi_its_cam_msgs/msg/PosLonCarr.msg | 33 +----- .../etsi_its_cam_msgs/msg/PosPillar.msg | 33 +----- .../msg/PositionOfOccupants.msg | 90 ++++------------ .../msg/PositionOfPillars.msg | 35 +----- .../msg/PositioningSolutionType.msg | 34 +----- .../msg/PostCrashSubCauseCode.msg | 33 +----- .../msg/ProtectedCommunicationZone.msg | 54 +++------- .../msg/ProtectedCommunicationZonesRSU.msg | 35 +----- .../etsi_its_cam_msgs/msg/ProtectedZoneID.msg | 31 +----- .../msg/ProtectedZoneRadius.msg | 37 +------ .../msg/ProtectedZoneType.msg | 31 +----- .../etsi_its_cam_msgs/msg/PtActivation.msg | 39 ++----- .../msg/PtActivationData.msg | 33 +----- .../msg/PtActivationType.msg | 35 +----- .../msg/PublicTransportContainer.msg | 41 ++----- .../msg/RSUContainerHighFrequency.msg | 38 ++----- .../msg/ReferencePosition.msg | 43 ++------ .../msg/RelevanceDistance.msg | 46 ++------ .../msg/RelevanceTrafficDirection.msg | 30 +----- .../msg/RequestResponseIndication.msg | 30 +----- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/RescueContainer.msg | 35 +----- .../etsi_its_cam_msgs/msg/RestrictedTypes.msg | 35 +----- .../etsi_its_cam_msgs/msg/RoadType.msg | 34 +----- .../msg/RoadWorksContainerBasic.msg | 45 ++------ .../msg/RoadworksSubCauseCode.msg | 33 +----- .../msg/SafetyCarContainer.msg | 49 +++------ .../etsi_its_cam_msgs/msg/SemiAxisLength.msg | 33 +----- .../etsi_its_cam_msgs/msg/SequenceNumber.msg | 31 +----- .../msg/SignalViolationSubCauseCode.msg | 33 +----- .../msg/SlowVehicleSubCauseCode.msg | 33 +----- .../msg/SpecialTransportContainer.msg | 39 ++----- .../msg/SpecialTransportType.msg | 32 +----- .../msg/SpecialVehicleContainer.msg | 59 ++-------- etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg | 39 ++----- .../etsi_its_cam_msgs/msg/SpeedConfidence.msg | 33 +----- .../etsi_its_cam_msgs/msg/SpeedLimit.msg | 33 +----- .../etsi_its_cam_msgs/msg/SpeedValue.msg | 33 +----- .../etsi_its_cam_msgs/msg/StationID.msg | 31 +----- .../etsi_its_cam_msgs/msg/StationType.msg | 34 +----- .../etsi_its_cam_msgs/msg/StationarySince.msg | 38 +------ .../msg/StationaryVehicleSubCauseCode.msg | 33 +----- .../msg/SteeringWheelAngle.msg | 39 ++----- .../msg/SteeringWheelAngleConfidence.msg | 33 +----- .../msg/SteeringWheelAngleValue.msg | 33 +----- .../msg/SubCauseCodeType.msg | 31 +----- .../etsi_its_cam_msgs/msg/Temperature.msg | 37 +------ .../etsi_its_cam_msgs/msg/TimestampIts.msg | 35 +----- .../etsi_its_cam_msgs/msg/Traces.msg | 35 +----- .../msg/TrafficConditionSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/TrafficRule.msg | 31 +----- .../msg/TransmissionInterval.msg | 33 +----- .../etsi_its_cam_msgs/msg/TurningRadius.msg | 35 +----- etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg | 32 +----- .../msg/ValidityDuration.msg | 33 +----- .../msg/VehicleBreakdownSubCauseCode.msg | 33 +----- .../msg/VehicleIdentification.msg | 52 +++------ .../etsi_its_cam_msgs/msg/VehicleLength.msg | 39 ++----- .../msg/VehicleLengthConfidenceIndication.msg | 30 +----- .../msg/VehicleLengthValue.msg | 33 +----- .../etsi_its_cam_msgs/msg/VehicleMass.msg | 33 +----- .../etsi_its_cam_msgs/msg/VehicleRole.msg | 36 +------ .../etsi_its_cam_msgs/msg/VehicleWidth.msg | 33 +----- .../msg/VerticalAcceleration.msg | 39 ++----- .../msg/VerticalAccelerationValue.msg | 33 +----- .../etsi_its_cam_msgs/msg/WMInumber.msg | 33 +----- .../msg/WheelBaseVehicle.msg | 33 +----- .../msg/WrongWayDrivingSubCauseCode.msg | 33 +----- .../etsi_its_cam_msgs/msg/YawRate.msg | 39 ++----- .../msg/YawRateConfidence.msg | 40 +------ .../etsi_its_cam_msgs/msg/YawRateValue.msg | 33 +----- .../msg/AccelerationConfidence.msg | 33 +----- .../msg/AccelerationControl.msg | 40 +------ .../msg/AccidentSubCauseCode.msg | 33 +----- .../etsi_its_denm_msgs/msg/ActionID.msg | 39 ++----- ...seWeatherConditionAdhesionSubCauseCode.msg | 33 +----- ...ionExtremeWeatherConditionSubCauseCode.msg | 33 +----- ...therConditionPrecipitationSubCauseCode.msg | 33 +----- ...WeatherConditionVisibilitySubCauseCode.msg | 33 +----- .../msg/AlacarteContainer.msg | 60 +++-------- .../etsi_its_denm_msgs/msg/Altitude.msg | 39 ++----- .../msg/AltitudeConfidence.msg | 47 +------- .../etsi_its_denm_msgs/msg/AltitudeValue.msg | 33 +----- .../etsi_its_denm_msgs/msg/CauseCode.msg | 40 ++----- .../etsi_its_denm_msgs/msg/CauseCodeType.msg | 61 +---------- .../msg/CenDsrcTollingZone.msg | 44 ++------ .../msg/CenDsrcTollingZoneID.msg | 31 +----- .../etsi_its_denm_msgs/msg/ClosedLanes.msg | 48 ++------- .../msg/CollisionRiskSubCauseCode.msg | 33 +----- .../etsi_its_denm_msgs/msg/Curvature.msg | 39 ++----- .../msg/CurvatureCalculationMode.msg | 30 +----- .../msg/CurvatureConfidence.msg | 39 +------ .../etsi_its_denm_msgs/msg/CurvatureValue.msg | 33 +----- etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg | 39 ++----- .../msg/DangerousEndOfQueueSubCauseCode.msg | 33 +----- .../msg/DangerousGoodsBasic.msg | 63 ++--------- .../msg/DangerousGoodsExtended.msg | 63 +++-------- .../msg/DangerousSituationSubCauseCode.msg | 33 +----- ...alizedEnvironmentalNotificationMessage.msg | 49 +++------ .../etsi_its_denm_msgs/msg/DeltaAltitude.msg | 33 +----- .../etsi_its_denm_msgs/msg/DeltaLatitude.msg | 33 +----- .../etsi_its_denm_msgs/msg/DeltaLongitude.msg | 33 +----- .../msg/DeltaReferencePosition.msg | 41 ++----- .../etsi_its_denm_msgs/msg/DigitalMap.msg | 35 +----- .../etsi_its_denm_msgs/msg/DriveDirection.msg | 30 +----- .../msg/DrivingLaneStatus.msg | 34 +----- .../msg/EmbarkationStatus.msg | 31 +----- .../msg/EmergencyPriority.msg | 32 +----- ...mergencyVehicleApproachingSubCauseCode.msg | 33 +----- .../msg/EnergyStorageType.msg | 32 +----- .../etsi_its_denm_msgs/msg/EventHistory.msg | 35 +----- .../etsi_its_denm_msgs/msg/EventPoint.msg | 43 ++------ .../etsi_its_denm_msgs/msg/ExteriorLights.msg | 41 +------ .../msg/HardShoulderStatus.msg | 30 +----- ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 33 +----- ...dousLocationDangerousCurveSubCauseCode.msg | 33 +----- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 33 +----- ...usLocationSurfaceConditionSubCauseCode.msg | 33 +----- .../etsi_its_denm_msgs/msg/Heading.msg | 39 ++----- .../msg/HeadingConfidence.msg | 33 +----- .../etsi_its_denm_msgs/msg/HeadingValue.msg | 41 ++----- .../etsi_its_denm_msgs/msg/HeightLonCarr.msg | 33 +----- .../HumanPresenceOnTheRoadSubCauseCode.msg | 33 +----- .../msg/HumanProblemSubCauseCode.msg | 33 +----- .../msg/ImpactReductionContainer.msg | 59 +++------- .../msg/InformationQuality.msg | 33 +----- .../etsi_its_denm_msgs/msg/ItineraryPath.msg | 35 +----- .../etsi_its_denm_msgs/msg/ItsPduHeader.msg | 37 ++----- .../etsi_its_denm_msgs/msg/LanePosition.msg | 34 +----- .../msg/LateralAcceleration.msg | 39 ++----- .../msg/LateralAccelerationValue.msg | 33 +----- .../etsi_its_denm_msgs/msg/Latitude.msg | 33 +----- .../msg/LightBarSirenInUse.msg | 35 +----- .../msg/LocationContainer.msg | 50 +++------ .../etsi_its_denm_msgs/msg/Longitude.msg | 33 +----- .../msg/LongitudinalAcceleration.msg | 39 ++----- .../msg/LongitudinalAccelerationValue.msg | 33 +----- .../msg/ManagementContainer.msg | 66 ++++-------- .../msg/NumberOfOccupants.msg | 33 +----- .../msg/OpeningDaysHours.msg | 31 +----- .../etsi_its_denm_msgs/msg/PathDeltaTime.msg | 37 +------ .../etsi_its_denm_msgs/msg/PathHistory.msg | 35 +----- .../etsi_its_denm_msgs/msg/PathPoint.msg | 41 ++----- .../msg/PerformanceClass.msg | 33 +----- .../etsi_its_denm_msgs/msg/PhoneNumber.msg | 33 +----- .../etsi_its_denm_msgs/msg/PosCentMass.msg | 33 +----- .../msg/PosConfidenceEllipse.msg | 41 ++----- .../etsi_its_denm_msgs/msg/PosFrontAx.msg | 33 +----- .../etsi_its_denm_msgs/msg/PosLonCarr.msg | 33 +----- .../etsi_its_denm_msgs/msg/PosPillar.msg | 33 +----- .../msg/PositionOfOccupants.msg | 90 ++++------------ .../msg/PositionOfPillars.msg | 35 +----- .../msg/PositioningSolutionType.msg | 34 +----- .../msg/PostCrashSubCauseCode.msg | 33 +----- .../msg/ProtectedCommunicationZone.msg | 54 +++------- .../msg/ProtectedCommunicationZonesRSU.msg | 35 +----- .../msg/ProtectedZoneID.msg | 31 +----- .../msg/ProtectedZoneRadius.msg | 37 +------ .../msg/ProtectedZoneType.msg | 31 +----- .../etsi_its_denm_msgs/msg/PtActivation.msg | 39 ++----- .../msg/PtActivationData.msg | 33 +----- .../msg/PtActivationType.msg | 35 +----- .../etsi_its_denm_msgs/msg/ReferenceDenms.msg | 35 +----- .../msg/ReferencePosition.msg | 43 ++------ .../msg/RelevanceDistance.msg | 46 ++------ .../msg/RelevanceTrafficDirection.msg | 30 +----- .../msg/RequestResponseIndication.msg | 30 +----- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 33 +----- .../msg/RestrictedTypes.msg | 35 +----- .../etsi_its_denm_msgs/msg/RoadType.msg | 34 +----- .../msg/RoadWorksContainerExtended.msg | 71 ++++-------- .../msg/RoadworksSubCauseCode.msg | 33 +----- .../etsi_its_denm_msgs/msg/SemiAxisLength.msg | 33 +----- .../etsi_its_denm_msgs/msg/SequenceNumber.msg | 31 +----- .../msg/SignalViolationSubCauseCode.msg | 33 +----- .../msg/SituationContainer.msg | 48 ++------- .../msg/SlowVehicleSubCauseCode.msg | 33 +----- .../msg/SpecialTransportType.msg | 32 +----- .../etsi_its_denm_msgs/msg/Speed.msg | 39 ++----- .../msg/SpeedConfidence.msg | 33 +----- .../etsi_its_denm_msgs/msg/SpeedLimit.msg | 33 +----- .../etsi_its_denm_msgs/msg/SpeedValue.msg | 33 +----- .../etsi_its_denm_msgs/msg/StationID.msg | 31 +----- .../etsi_its_denm_msgs/msg/StationType.msg | 34 +----- .../msg/StationarySince.msg | 38 +------ .../msg/StationaryVehicleContainer.msg | 59 +++------- .../msg/StationaryVehicleSubCauseCode.msg | 33 +----- .../msg/SteeringWheelAngle.msg | 39 ++----- .../msg/SteeringWheelAngleConfidence.msg | 33 +----- .../msg/SteeringWheelAngleValue.msg | 33 +----- .../msg/SubCauseCodeType.msg | 31 +----- .../etsi_its_denm_msgs/msg/Temperature.msg | 37 +------ .../etsi_its_denm_msgs/msg/Termination.msg | 30 +----- .../etsi_its_denm_msgs/msg/TimestampIts.msg | 35 +----- .../etsi_its_denm_msgs/msg/Traces.msg | 35 +----- .../msg/TrafficConditionSubCauseCode.msg | 33 +----- .../etsi_its_denm_msgs/msg/TrafficRule.msg | 31 +----- .../msg/TransmissionInterval.msg | 33 +----- .../etsi_its_denm_msgs/msg/TurningRadius.msg | 35 +----- etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg | 32 +----- .../msg/ValidityDuration.msg | 33 +----- .../msg/VehicleBreakdownSubCauseCode.msg | 33 +----- .../msg/VehicleIdentification.msg | 52 +++------ .../etsi_its_denm_msgs/msg/VehicleLength.msg | 39 ++----- .../msg/VehicleLengthConfidenceIndication.msg | 30 +----- .../msg/VehicleLengthValue.msg | 33 +----- .../etsi_its_denm_msgs/msg/VehicleMass.msg | 33 +----- .../etsi_its_denm_msgs/msg/VehicleRole.msg | 36 +------ .../etsi_its_denm_msgs/msg/VehicleWidth.msg | 33 +----- .../msg/VerticalAcceleration.msg | 39 ++----- .../msg/VerticalAccelerationValue.msg | 33 +----- .../etsi_its_denm_msgs/msg/WMInumber.msg | 33 +----- .../msg/WheelBaseVehicle.msg | 33 +----- .../msg/WrongWayDrivingSubCauseCode.msg | 33 +----- .../etsi_its_denm_msgs/msg/YawRate.msg | 39 ++----- .../msg/YawRateConfidence.msg | 40 +------ .../etsi_its_denm_msgs/msg/YawRateValue.msg | 33 +----- 598 files changed, 3158 insertions(+), 18529 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h index 0125b5c14..5c1960beb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AccelerationConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AccelerationConfidence(const AccelerationConfidence_t& in, cam_msgs::AccelerationConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccelerationConfidence(const cam_msgs::AccelerationConfidence& in, AccelerationConfidence_t& out) { - memset(&out, 0, sizeof(AccelerationConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h index 8eecdd8fe..c8c3b2fc0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING AccelerationControl -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AccelerationControl(const AccelerationControl_t& in, cam_msgs::AccelerationControl& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_AccelerationControl(const cam_msgs::AccelerationControl& in, AccelerationControl_t& out) { - memset(&out, 0, sizeof(AccelerationControl_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h index dd2636450..15a251cff 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AccidentSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AccidentSubCauseCode(const AccidentSubCauseCode_t& in, cam_msgs::AccidentSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccidentSubCauseCode(const cam_msgs::AccidentSubCauseCode& in, AccidentSubCauseCode_t& out) { - memset(&out, 0, sizeof(AccidentSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index 8e0c1c721..f38c0fe50 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ActionID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ActionID(const ActionID_t& in, cam_msgs::ActionID& out) { - toRos_StationID(in.originatingStationID, out.originating_station_id); toRos_SequenceNumber(in.sequenceNumber, out.sequence_number); } void toStruct_ActionID(const cam_msgs::ActionID& in, ActionID_t& out) { - memset(&out, 0, sizeof(ActionID_t)); toStruct_StationID(in.originating_station_id, out.originatingStationID); toStruct_SequenceNumber(in.sequence_number, out.sequenceNumber); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index 9a3f0aaae..de3a68f59 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionAdhesionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionAdhesionSubCauseCode(const AdverseWeatherCondition_AdhesionSubCauseCode_t& in, cam_msgs::AdverseWeatherConditionAdhesionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionAdhesionSubCauseCode(const cam_msgs::AdverseWeatherConditionAdhesionSubCauseCode& in, AdverseWeatherCondition_AdhesionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_AdhesionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 28d36aa16..919ca03c1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& in, cam_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const cam_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& in, AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index 02d1b6425..b7d4a2f58 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionPrecipitationSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionPrecipitationSubCauseCode(const AdverseWeatherCondition_PrecipitationSubCauseCode_t& in, cam_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionPrecipitationSubCauseCode(const cam_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& in, AdverseWeatherCondition_PrecipitationSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_PrecipitationSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index 887ceba71..4c7d86d27 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionVisibilitySubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionVisibilitySubCauseCode(const AdverseWeatherCondition_VisibilitySubCauseCode_t& in, cam_msgs::AdverseWeatherConditionVisibilitySubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionVisibilitySubCauseCode(const cam_msgs::AdverseWeatherConditionVisibilitySubCauseCode& in, AdverseWeatherCondition_VisibilitySubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_VisibilitySubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index 3cadcf311..f8cece502 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Altitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Altitude(const Altitude_t& in, cam_msgs::Altitude& out) { - toRos_AltitudeValue(in.altitudeValue, out.altitude_value); toRos_AltitudeConfidence(in.altitudeConfidence, out.altitude_confidence); } void toStruct_Altitude(const cam_msgs::Altitude& in, Altitude_t& out) { - memset(&out, 0, sizeof(Altitude_t)); toStruct_AltitudeValue(in.altitude_value, out.altitudeValue); toStruct_AltitudeConfidence(in.altitude_confidence, out.altitudeConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h index 1da533614..fb35b2a71 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED AltitudeConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AltitudeConfidence(const AltitudeConfidence_t& in, cam_msgs::AltitudeConfidence& out) { - out.value = in; } void toStruct_AltitudeConfidence(const cam_msgs::AltitudeConfidence& in, AltitudeConfidence_t& out) { - memset(&out, 0, sizeof(AltitudeConfidence_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h index 43bd12a66..f07dd495e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AltitudeValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AltitudeValue(const AltitudeValue_t& in, cam_msgs::AltitudeValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AltitudeValue(const cam_msgs::AltitudeValue& in, AltitudeValue_t& out) { - memset(&out, 0, sizeof(AltitudeValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index 11d2fb702..6a7daf9ff 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE BasicContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_BasicContainer(const BasicContainer_t& in, cam_msgs::BasicContainer& out) { - toRos_StationType(in.stationType, out.station_type); toRos_ReferencePosition(in.referencePosition, out.reference_position); } void toStruct_BasicContainer(const cam_msgs::BasicContainer& in, BasicContainer_t& out) { - memset(&out, 0, sizeof(BasicContainer_t)); toStruct_StationType(in.station_type, out.stationType); toStruct_ReferencePosition(in.reference_position, out.referencePosition); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index 3d9247355..b29c26189 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE BasicVehicleContainerHighFrequency -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -55,7 +34,6 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_BasicVehicleContainerHighFrequency(const BasicVehicleContainerHighFrequency_t& in, cam_msgs::BasicVehicleContainerHighFrequency& out) { - toRos_Heading(in.heading, out.heading); toRos_Speed(in.speed, out.speed); toRos_DriveDirection(in.driveDirection, out.drive_direction); @@ -69,41 +47,33 @@ void toRos_BasicVehicleContainerHighFrequency(const BasicVehicleContainerHighFre toRos_AccelerationControl(*in.accelerationControl, out.acceleration_control); out.acceleration_control_is_present = true; } - if (in.lanePosition) { toRos_LanePosition(*in.lanePosition, out.lane_position); out.lane_position_is_present = true; } - if (in.steeringWheelAngle) { toRos_SteeringWheelAngle(*in.steeringWheelAngle, out.steering_wheel_angle); out.steering_wheel_angle_is_present = true; } - if (in.lateralAcceleration) { toRos_LateralAcceleration(*in.lateralAcceleration, out.lateral_acceleration); out.lateral_acceleration_is_present = true; } - if (in.verticalAcceleration) { toRos_VerticalAcceleration(*in.verticalAcceleration, out.vertical_acceleration); out.vertical_acceleration_is_present = true; } - if (in.performanceClass) { toRos_PerformanceClass(*in.performanceClass, out.performance_class); out.performance_class_is_present = true; } - if (in.cenDsrcTollingZone) { toRos_CenDsrcTollingZone(*in.cenDsrcTollingZone, out.cen_dsrc_tolling_zone); out.cen_dsrc_tolling_zone_is_present = true; } - } void toStruct_BasicVehicleContainerHighFrequency(const cam_msgs::BasicVehicleContainerHighFrequency& in, BasicVehicleContainerHighFrequency_t& out) { - memset(&out, 0, sizeof(BasicVehicleContainerHighFrequency_t)); toStruct_Heading(in.heading, out.heading); @@ -116,47 +86,33 @@ void toStruct_BasicVehicleContainerHighFrequency(const cam_msgs::BasicVehicleCon toStruct_CurvatureCalculationMode(in.curvature_calculation_mode, out.curvatureCalculationMode); toStruct_YawRate(in.yaw_rate, out.yawRate); if (in.acceleration_control_is_present) { - AccelerationControl_t acceleration_control; - toStruct_AccelerationControl(in.acceleration_control, acceleration_control); - out.accelerationControl = new AccelerationControl_t(acceleration_control); + out.accelerationControl = (AccelerationControl_t*) calloc(1, sizeof(AccelerationControl_t)); + toStruct_AccelerationControl(in.acceleration_control, *out.accelerationControl); } - if (in.lane_position_is_present) { - LanePosition_t lane_position; - toStruct_LanePosition(in.lane_position, lane_position); - out.lanePosition = new LanePosition_t(lane_position); + out.lanePosition = (LanePosition_t*) calloc(1, sizeof(LanePosition_t)); + toStruct_LanePosition(in.lane_position, *out.lanePosition); } - if (in.steering_wheel_angle_is_present) { - SteeringWheelAngle_t steering_wheel_angle; - toStruct_SteeringWheelAngle(in.steering_wheel_angle, steering_wheel_angle); - out.steeringWheelAngle = new SteeringWheelAngle_t(steering_wheel_angle); + out.steeringWheelAngle = (SteeringWheelAngle_t*) calloc(1, sizeof(SteeringWheelAngle_t)); + toStruct_SteeringWheelAngle(in.steering_wheel_angle, *out.steeringWheelAngle); } - if (in.lateral_acceleration_is_present) { - LateralAcceleration_t lateral_acceleration; - toStruct_LateralAcceleration(in.lateral_acceleration, lateral_acceleration); - out.lateralAcceleration = new LateralAcceleration_t(lateral_acceleration); + out.lateralAcceleration = (LateralAcceleration_t*) calloc(1, sizeof(LateralAcceleration_t)); + toStruct_LateralAcceleration(in.lateral_acceleration, *out.lateralAcceleration); } - if (in.vertical_acceleration_is_present) { - VerticalAcceleration_t vertical_acceleration; - toStruct_VerticalAcceleration(in.vertical_acceleration, vertical_acceleration); - out.verticalAcceleration = new VerticalAcceleration_t(vertical_acceleration); + out.verticalAcceleration = (VerticalAcceleration_t*) calloc(1, sizeof(VerticalAcceleration_t)); + toStruct_VerticalAcceleration(in.vertical_acceleration, *out.verticalAcceleration); } - if (in.performance_class_is_present) { - PerformanceClass_t performance_class; - toStruct_PerformanceClass(in.performance_class, performance_class); - out.performanceClass = new PerformanceClass_t(performance_class); + out.performanceClass = (PerformanceClass_t*) calloc(1, sizeof(PerformanceClass_t)); + toStruct_PerformanceClass(in.performance_class, *out.performanceClass); } - if (in.cen_dsrc_tolling_zone_is_present) { - CenDsrcTollingZone_t cen_dsrc_tolling_zone; - toStruct_CenDsrcTollingZone(in.cen_dsrc_tolling_zone, cen_dsrc_tolling_zone); - out.cenDsrcTollingZone = new CenDsrcTollingZone_t(cen_dsrc_tolling_zone); + out.cenDsrcTollingZone = (CenDsrcTollingZone_t*) calloc(1, sizeof(CenDsrcTollingZone_t)); + toStruct_CenDsrcTollingZone(in.cen_dsrc_tolling_zone, *out.cenDsrcTollingZone); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index b2aff721f..9e75547dd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE BasicVehicleContainerLowFrequency -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,14 +21,12 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_BasicVehicleContainerLowFrequency(const BasicVehicleContainerLowFrequency_t& in, cam_msgs::BasicVehicleContainerLowFrequency& out) { - toRos_VehicleRole(in.vehicleRole, out.vehicle_role); toRos_ExteriorLights(in.exteriorLights, out.exterior_lights); toRos_PathHistory(in.pathHistory, out.path_history); } void toStruct_BasicVehicleContainerLowFrequency(const cam_msgs::BasicVehicleContainerLowFrequency& in, BasicVehicleContainerLowFrequency_t& out) { - memset(&out, 0, sizeof(BasicVehicleContainerLowFrequency_t)); toStruct_VehicleRole(in.vehicle_role, out.vehicleRole); @@ -57,4 +34,4 @@ void toStruct_BasicVehicleContainerLowFrequency(const cam_msgs::BasicVehicleCont toStruct_PathHistory(in.path_history, out.pathHistory); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index 8d5806e82..bab31d2f7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -1,31 +1,11 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CAM +// The root data frame for cooperative awareness messages -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +21,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CAM(const CAM_t& in, cam_msgs::CAM& out) { - toRos_ItsPduHeader(in.header, out.header); toRos_CoopAwareness(in.cam, out.cam); } void toStruct_CAM(const cam_msgs::CAM& in, CAM_t& out) { - memset(&out, 0, sizeof(CAM_t)); toStruct_ItsPduHeader(in.header, out.header); toStruct_CoopAwareness(in.cam, out.cam); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index 39ee0e322..3eaa415ae 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CamParameters -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,39 +22,31 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CamParameters(const CamParameters_t& in, cam_msgs::CamParameters& out) { - toRos_BasicContainer(in.basicContainer, out.basic_container); toRos_HighFrequencyContainer(in.highFrequencyContainer, out.high_frequency_container); if (in.lowFrequencyContainer) { toRos_LowFrequencyContainer(*in.lowFrequencyContainer, out.low_frequency_container); out.low_frequency_container_is_present = true; } - if (in.specialVehicleContainer) { toRos_SpecialVehicleContainer(*in.specialVehicleContainer, out.special_vehicle_container); out.special_vehicle_container_is_present = true; } - } void toStruct_CamParameters(const cam_msgs::CamParameters& in, CamParameters_t& out) { - memset(&out, 0, sizeof(CamParameters_t)); toStruct_BasicContainer(in.basic_container, out.basicContainer); toStruct_HighFrequencyContainer(in.high_frequency_container, out.highFrequencyContainer); if (in.low_frequency_container_is_present) { - LowFrequencyContainer_t low_frequency_container; - toStruct_LowFrequencyContainer(in.low_frequency_container, low_frequency_container); - out.lowFrequencyContainer = new LowFrequencyContainer_t(low_frequency_container); + out.lowFrequencyContainer = (LowFrequencyContainer_t*) calloc(1, sizeof(LowFrequencyContainer_t)); + toStruct_LowFrequencyContainer(in.low_frequency_container, *out.lowFrequencyContainer); } - if (in.special_vehicle_container_is_present) { - SpecialVehicleContainer_t special_vehicle_container; - toStruct_SpecialVehicleContainer(in.special_vehicle_container, special_vehicle_container); - out.specialVehicleContainer = new SpecialVehicleContainer_t(special_vehicle_container); + out.specialVehicleContainer = (SpecialVehicleContainer_t*) calloc(1, sizeof(SpecialVehicleContainer_t)); + toStruct_SpecialVehicleContainer(in.special_vehicle_container, *out.specialVehicleContainer); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h index 626031433..b2551d9b5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CauseCode(const CauseCode_t& in, cam_msgs::CauseCode& out) { - toRos_CauseCodeType(in.causeCode, out.cause_code); toRos_SubCauseCodeType(in.subCauseCode, out.sub_cause_code); } void toStruct_CauseCode(const cam_msgs::CauseCode& in, CauseCode_t& out) { - memset(&out, 0, sizeof(CauseCode_t)); toStruct_CauseCodeType(in.cause_code, out.causeCode); toStruct_SubCauseCodeType(in.sub_cause_code, out.subCauseCode); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h index 7007cb664..fc379e214 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER CauseCodeType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CauseCodeType(const CauseCodeType_t& in, cam_msgs::CauseCodeType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CauseCodeType(const cam_msgs::CauseCodeType& in, CauseCodeType_t& out) { - memset(&out, 0, sizeof(CauseCodeType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index a715a14e0..175ad1ea3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CenDsrcTollingZone -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,28 +21,23 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CenDsrcTollingZone(const CenDsrcTollingZone_t& in, cam_msgs::CenDsrcTollingZone& out) { - toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.cenDsrcTollingZoneID) { toRos_CenDsrcTollingZoneID(*in.cenDsrcTollingZoneID, out.cen_dsrc_tolling_zone_id); out.cen_dsrc_tolling_zone_id_is_present = true; } - } void toStruct_CenDsrcTollingZone(const cam_msgs::CenDsrcTollingZone& in, CenDsrcTollingZone_t& out) { - memset(&out, 0, sizeof(CenDsrcTollingZone_t)); toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.cen_dsrc_tolling_zone_id_is_present) { - CenDsrcTollingZoneID_t cen_dsrc_tolling_zone_id; - toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, cen_dsrc_tolling_zone_id); - out.cenDsrcTollingZoneID = new CenDsrcTollingZoneID_t(cen_dsrc_tolling_zone_id); + out.cenDsrcTollingZoneID = (CenDsrcTollingZoneID_t*) calloc(1, sizeof(CenDsrcTollingZoneID_t)); + toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, *out.cenDsrcTollingZoneID); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h index 4b0e2e7d9..2a183937b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// TYPEALIAS CenDsrcTollingZoneID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #ifdef ROS1 @@ -36,17 +15,17 @@ namespace cam_msgs = etsi_its_cam_msgs; namespace cam_msgs = etsi_its_cam_msgs::msg; #endif + namespace etsi_its_cam_conversion { void toRos_CenDsrcTollingZoneID(const CenDsrcTollingZoneID_t& in, cam_msgs::CenDsrcTollingZoneID& out) { - toRos_ProtectedZoneID(in, out.value); } void toStruct_CenDsrcTollingZoneID(const cam_msgs::CenDsrcTollingZoneID& in, CenDsrcTollingZoneID_t& out) { - memset(&out, 0, sizeof(CenDsrcTollingZoneID_t)); + toStruct_ProtectedZoneID(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h index f6e6aa111..1975333eb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ClosedLanes -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,46 +21,35 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ClosedLanes(const ClosedLanes_t& in, cam_msgs::ClosedLanes& out) { - if (in.innerhardShoulderStatus) { toRos_HardShoulderStatus(*in.innerhardShoulderStatus, out.innerhard_shoulder_status); out.innerhard_shoulder_status_is_present = true; } - if (in.outerhardShoulderStatus) { toRos_HardShoulderStatus(*in.outerhardShoulderStatus, out.outerhard_shoulder_status); out.outerhard_shoulder_status_is_present = true; } - if (in.drivingLaneStatus) { toRos_DrivingLaneStatus(*in.drivingLaneStatus, out.driving_lane_status); out.driving_lane_status_is_present = true; } - } void toStruct_ClosedLanes(const cam_msgs::ClosedLanes& in, ClosedLanes_t& out) { - memset(&out, 0, sizeof(ClosedLanes_t)); if (in.innerhard_shoulder_status_is_present) { - HardShoulderStatus_t innerhard_shoulder_status; - toStruct_HardShoulderStatus(in.innerhard_shoulder_status, innerhard_shoulder_status); - out.innerhardShoulderStatus = new HardShoulderStatus_t(innerhard_shoulder_status); + out.innerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); + toStruct_HardShoulderStatus(in.innerhard_shoulder_status, *out.innerhardShoulderStatus); } - if (in.outerhard_shoulder_status_is_present) { - HardShoulderStatus_t outerhard_shoulder_status; - toStruct_HardShoulderStatus(in.outerhard_shoulder_status, outerhard_shoulder_status); - out.outerhardShoulderStatus = new HardShoulderStatus_t(outerhard_shoulder_status); + out.outerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); + toStruct_HardShoulderStatus(in.outerhard_shoulder_status, *out.outerhardShoulderStatus); } - if (in.driving_lane_status_is_present) { - DrivingLaneStatus_t driving_lane_status; - toStruct_DrivingLaneStatus(in.driving_lane_status, driving_lane_status); - out.drivingLaneStatus = new DrivingLaneStatus_t(driving_lane_status); + out.drivingLaneStatus = (DrivingLaneStatus_t*) calloc(1, sizeof(DrivingLaneStatus_t)); + toStruct_DrivingLaneStatus(in.driving_lane_status, *out.drivingLaneStatus); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h index 57d136039..d7c4ab0ba 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER CollisionRiskSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CollisionRiskSubCauseCode(const CollisionRiskSubCauseCode_t& in, cam_msgs::CollisionRiskSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CollisionRiskSubCauseCode(const cam_msgs::CollisionRiskSubCauseCode& in, CollisionRiskSubCauseCode_t& out) { - memset(&out, 0, sizeof(CollisionRiskSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h index ab993b23e..f56b4a066 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CoopAwareness -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CoopAwareness(const CoopAwareness_t& in, cam_msgs::CoopAwareness& out) { - toRos_GenerationDeltaTime(in.generationDeltaTime, out.generation_delta_time); toRos_CamParameters(in.camParameters, out.cam_parameters); } void toStruct_CoopAwareness(const cam_msgs::CoopAwareness& in, CoopAwareness_t& out) { - memset(&out, 0, sizeof(CoopAwareness_t)); toStruct_GenerationDeltaTime(in.generation_delta_time, out.generationDeltaTime); toStruct_CamParameters(in.cam_parameters, out.camParameters); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 6527951e2..eff4e3b81 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Curvature -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Curvature(const Curvature_t& in, cam_msgs::Curvature& out) { - toRos_CurvatureValue(in.curvatureValue, out.curvature_value); toRos_CurvatureConfidence(in.curvatureConfidence, out.curvature_confidence); } void toStruct_Curvature(const cam_msgs::Curvature& in, Curvature_t& out) { - memset(&out, 0, sizeof(Curvature_t)); toStruct_CurvatureValue(in.curvature_value, out.curvatureValue); toStruct_CurvatureConfidence(in.curvature_confidence, out.curvatureConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h index 3e9580068..8076507a4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED CurvatureCalculationMode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CurvatureCalculationMode(const CurvatureCalculationMode_t& in, cam_msgs::CurvatureCalculationMode& out) { - out.value = in; } void toStruct_CurvatureCalculationMode(const cam_msgs::CurvatureCalculationMode& in, CurvatureCalculationMode_t& out) { - memset(&out, 0, sizeof(CurvatureCalculationMode_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h index 849da3ea5..d3ef7cbc3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED CurvatureConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CurvatureConfidence(const CurvatureConfidence_t& in, cam_msgs::CurvatureConfidence& out) { - out.value = in; } void toStruct_CurvatureConfidence(const cam_msgs::CurvatureConfidence& in, CurvatureConfidence_t& out) { - memset(&out, 0, sizeof(CurvatureConfidence_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h index da36cf199..40e166b7c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER CurvatureValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CurvatureValue(const CurvatureValue_t& in, cam_msgs::CurvatureValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CurvatureValue(const cam_msgs::CurvatureValue& in, CurvatureValue_t& out) { - memset(&out, 0, sizeof(CurvatureValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h index 1f9239a03..a9c2dd61e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DangerousEndOfQueueSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousEndOfQueueSubCauseCode(const DangerousEndOfQueueSubCauseCode_t& in, cam_msgs::DangerousEndOfQueueSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousEndOfQueueSubCauseCode(const cam_msgs::DangerousEndOfQueueSubCauseCode& in, DangerousEndOfQueueSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousEndOfQueueSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h index b2571af0d..2f9bfb5ab 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED DangerousGoodsBasic -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousGoodsBasic(const DangerousGoodsBasic_t& in, cam_msgs::DangerousGoodsBasic& out) { - out.value = in; } void toStruct_DangerousGoodsBasic(const cam_msgs::DangerousGoodsBasic& in, DangerousGoodsBasic_t& out) { - memset(&out, 0, sizeof(DangerousGoodsBasic_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h index 1ca5bec78..40bc035d6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DangerousGoodsContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #ifdef ROS1 @@ -40,15 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousGoodsContainer(const DangerousGoodsContainer_t& in, cam_msgs::DangerousGoodsContainer& out) { - toRos_DangerousGoodsBasic(in.dangerousGoodsBasic, out.dangerous_goods_basic); } void toStruct_DangerousGoodsContainer(const cam_msgs::DangerousGoodsContainer& in, DangerousGoodsContainer_t& out) { - memset(&out, 0, sizeof(DangerousGoodsContainer_t)); toStruct_DangerousGoodsBasic(in.dangerous_goods_basic, out.dangerousGoodsBasic); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index a61abaa25..81d6f388c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -1,39 +1,24 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DangerousGoodsExtended -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include +#include #include +#include #include +#include #include +#include #include +#include #include #include +#include #include #ifdef ROS1 #include @@ -47,7 +32,6 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, cam_msgs::DangerousGoodsExtended& out) { - toRos_DangerousGoodsBasic(in.dangerousGoodsType, out.dangerous_goods_type); etsi_its_primitives_conversion::toRos_INTEGER(in.unNumber, out.un_number); etsi_its_primitives_conversion::toRos_BOOLEAN(in.elevatedTemperature, out.elevated_temperature); @@ -57,21 +41,17 @@ void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, cam_msgs:: etsi_its_primitives_conversion::toRos_IA5String(*in.emergencyActionCode, out.emergency_action_code); out.emergency_action_code_is_present = true; } - if (in.phoneNumber) { toRos_PhoneNumber(*in.phoneNumber, out.phone_number); out.phone_number_is_present = true; } - if (in.companyName) { etsi_its_primitives_conversion::toRos_UTF8String(*in.companyName, out.company_name); out.company_name_is_present = true; } - } void toStruct_DangerousGoodsExtended(const cam_msgs::DangerousGoodsExtended& in, DangerousGoodsExtended_t& out) { - memset(&out, 0, sizeof(DangerousGoodsExtended_t)); toStruct_DangerousGoodsBasic(in.dangerous_goods_type, out.dangerousGoodsType); @@ -80,23 +60,17 @@ void toStruct_DangerousGoodsExtended(const cam_msgs::DangerousGoodsExtended& in, etsi_its_primitives_conversion::toStruct_BOOLEAN(in.tunnels_restricted, out.tunnelsRestricted); etsi_its_primitives_conversion::toStruct_BOOLEAN(in.limited_quantity, out.limitedQuantity); if (in.emergency_action_code_is_present) { - IA5String_t emergency_action_code; - etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, emergency_action_code); - out.emergencyActionCode = new IA5String_t(emergency_action_code); + out.emergencyActionCode = (IA5String_t*) calloc(1, sizeof(IA5String_t)); + etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, *out.emergencyActionCode); } - if (in.phone_number_is_present) { - PhoneNumber_t phone_number; - toStruct_PhoneNumber(in.phone_number, phone_number); - out.phoneNumber = new PhoneNumber_t(phone_number); + out.phoneNumber = (PhoneNumber_t*) calloc(1, sizeof(PhoneNumber_t)); + toStruct_PhoneNumber(in.phone_number, *out.phoneNumber); } - if (in.company_name_is_present) { - UTF8String_t company_name; - etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, company_name); - out.companyName = new UTF8String_t(company_name); + out.companyName = (UTF8String_t*) calloc(1, sizeof(UTF8String_t)); + etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, *out.companyName); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h index 3efe64189..298754886 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DangerousSituationSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousSituationSubCauseCode(const DangerousSituationSubCauseCode_t& in, cam_msgs::DangerousSituationSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousSituationSubCauseCode(const cam_msgs::DangerousSituationSubCauseCode& in, DangerousSituationSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousSituationSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h index 79bc30517..49a817b02 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DeltaAltitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaAltitude(const DeltaAltitude_t& in, cam_msgs::DeltaAltitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaAltitude(const cam_msgs::DeltaAltitude& in, DeltaAltitude_t& out) { - memset(&out, 0, sizeof(DeltaAltitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h index a0d157e7e..a2ccb471f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DeltaLatitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaLatitude(const DeltaLatitude_t& in, cam_msgs::DeltaLatitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLatitude(const cam_msgs::DeltaLatitude& in, DeltaLatitude_t& out) { - memset(&out, 0, sizeof(DeltaLatitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h index ca6ecb892..835cf3d6e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DeltaLongitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaLongitude(const DeltaLongitude_t& in, cam_msgs::DeltaLongitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLongitude(const cam_msgs::DeltaLongitude& in, DeltaLongitude_t& out) { - memset(&out, 0, sizeof(DeltaLongitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index ef26422a4..f0f809bd1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DeltaReferencePosition -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,14 +21,12 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaReferencePosition(const DeltaReferencePosition_t& in, cam_msgs::DeltaReferencePosition& out) { - toRos_DeltaLatitude(in.deltaLatitude, out.delta_latitude); toRos_DeltaLongitude(in.deltaLongitude, out.delta_longitude); toRos_DeltaAltitude(in.deltaAltitude, out.delta_altitude); } void toStruct_DeltaReferencePosition(const cam_msgs::DeltaReferencePosition& in, DeltaReferencePosition_t& out) { - memset(&out, 0, sizeof(DeltaReferencePosition_t)); toStruct_DeltaLatitude(in.delta_latitude, out.deltaLatitude); @@ -57,4 +34,4 @@ void toStruct_DeltaReferencePosition(const cam_msgs::DeltaReferencePosition& in, toStruct_DeltaAltitude(in.delta_altitude, out.deltaAltitude); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h index 1a1a1cffa..9df37e996 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF DigitalMap -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DigitalMap(const DigitalMap_t& in, cam_msgs::DigitalMap& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::ReferencePosition array; - toRos_ReferencePosition(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::ReferencePosition el; + toRos_ReferencePosition(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_DigitalMap(const cam_msgs::DigitalMap& in, DigitalMap_t& out) { - memset(&out, 0, sizeof(DigitalMap_t)); - for (int i = 0; i < in.array.size(); i++) { - ReferencePosition_t array; - toStruct_ReferencePosition(in.array[i], array); - ReferencePosition_t* array_ptr = new ReferencePosition_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); + toStruct_ReferencePosition(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h index 820f45185..ea7006322 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED DriveDirection -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DriveDirection(const DriveDirection_t& in, cam_msgs::DriveDirection& out) { - out.value = in; } void toStruct_DriveDirection(const cam_msgs::DriveDirection& in, DriveDirection_t& out) { - memset(&out, 0, sizeof(DriveDirection_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h index d17439b78..4451f1dbf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING DrivingLaneStatus -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DrivingLaneStatus(const DrivingLaneStatus_t& in, cam_msgs::DrivingLaneStatus& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_DrivingLaneStatus(const cam_msgs::DrivingLaneStatus& in, DrivingLaneStatus_t& out) { - memset(&out, 0, sizeof(DrivingLaneStatus_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h index d60b5b182..7e639372d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BOOLEAN EmbarkationStatus -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmbarkationStatus(const EmbarkationStatus_t& in, cam_msgs::EmbarkationStatus& out) { - etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value); } void toStruct_EmbarkationStatus(const cam_msgs::EmbarkationStatus& in, EmbarkationStatus_t& out) { - memset(&out, 0, sizeof(EmbarkationStatus_t)); + etsi_its_primitives_conversion::toStruct_BOOLEAN(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index 4ef09c64c..10f3eee7c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE EmergencyContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,37 +21,29 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmergencyContainer(const EmergencyContainer_t& in, cam_msgs::EmergencyContainer& out) { - toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); if (in.incidentIndication) { toRos_CauseCode(*in.incidentIndication, out.incident_indication); out.incident_indication_is_present = true; } - if (in.emergencyPriority) { toRos_EmergencyPriority(*in.emergencyPriority, out.emergency_priority); out.emergency_priority_is_present = true; } - } void toStruct_EmergencyContainer(const cam_msgs::EmergencyContainer& in, EmergencyContainer_t& out) { - memset(&out, 0, sizeof(EmergencyContainer_t)); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); if (in.incident_indication_is_present) { - CauseCode_t incident_indication; - toStruct_CauseCode(in.incident_indication, incident_indication); - out.incidentIndication = new CauseCode_t(incident_indication); + out.incidentIndication = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); + toStruct_CauseCode(in.incident_indication, *out.incidentIndication); } - if (in.emergency_priority_is_present) { - EmergencyPriority_t emergency_priority; - toStruct_EmergencyPriority(in.emergency_priority, emergency_priority); - out.emergencyPriority = new EmergencyPriority_t(emergency_priority); + out.emergencyPriority = (EmergencyPriority_t*) calloc(1, sizeof(EmergencyPriority_t)); + toStruct_EmergencyPriority(in.emergency_priority, *out.emergencyPriority); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h index 17e36a974..1f6dbfa79 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING EmergencyPriority -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmergencyPriority(const EmergencyPriority_t& in, cam_msgs::EmergencyPriority& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EmergencyPriority(const cam_msgs::EmergencyPriority& in, EmergencyPriority_t& out) { - memset(&out, 0, sizeof(EmergencyPriority_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 7da6a03d7..9062e0fc3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER EmergencyVehicleApproachingSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmergencyVehicleApproachingSubCauseCode(const EmergencyVehicleApproachingSubCauseCode_t& in, cam_msgs::EmergencyVehicleApproachingSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_EmergencyVehicleApproachingSubCauseCode(const cam_msgs::EmergencyVehicleApproachingSubCauseCode& in, EmergencyVehicleApproachingSubCauseCode_t& out) { - memset(&out, 0, sizeof(EmergencyVehicleApproachingSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h index b5a00b371..3d3f10c1a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING EnergyStorageType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EnergyStorageType(const EnergyStorageType_t& in, cam_msgs::EnergyStorageType& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EnergyStorageType(const cam_msgs::EnergyStorageType& in, EnergyStorageType_t& out) { - memset(&out, 0, sizeof(EnergyStorageType_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index 4785c8924..2ef1c6bcf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF EventHistory -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EventHistory(const EventHistory_t& in, cam_msgs::EventHistory& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::EventPoint array; - toRos_EventPoint(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::EventPoint el; + toRos_EventPoint(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_EventHistory(const cam_msgs::EventHistory& in, EventHistory_t& out) { - memset(&out, 0, sizeof(EventHistory_t)); - for (int i = 0; i < in.array.size(); i++) { - EventPoint_t array; - toStruct_EventPoint(in.array[i], array); - EventPoint_t* array_ptr = new EventPoint_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + EventPoint_t* el = (EventPoint_t*) calloc(1, sizeof(EventPoint_t)); + toStruct_EventPoint(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index c73f053cf..ebc2ba8c5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE EventPoint -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,28 +21,23 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EventPoint(const EventPoint_t& in, cam_msgs::EventPoint& out) { - toRos_DeltaReferencePosition(in.eventPosition, out.event_position); if (in.eventDeltaTime) { toRos_PathDeltaTime(*in.eventDeltaTime, out.event_delta_time); out.event_delta_time_is_present = true; } - toRos_InformationQuality(in.informationQuality, out.information_quality); } void toStruct_EventPoint(const cam_msgs::EventPoint& in, EventPoint_t& out) { - memset(&out, 0, sizeof(EventPoint_t)); toStruct_DeltaReferencePosition(in.event_position, out.eventPosition); if (in.event_delta_time_is_present) { - PathDeltaTime_t event_delta_time; - toStruct_PathDeltaTime(in.event_delta_time, event_delta_time); - out.eventDeltaTime = new PathDeltaTime_t(event_delta_time); + out.eventDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); + toStruct_PathDeltaTime(in.event_delta_time, *out.eventDeltaTime); } - toStruct_InformationQuality(in.information_quality, out.informationQuality); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h index 923274b83..6f22eafed 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING ExteriorLights -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ExteriorLights(const ExteriorLights_t& in, cam_msgs::ExteriorLights& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_ExteriorLights(const cam_msgs::ExteriorLights& in, ExteriorLights_t& out) { - memset(&out, 0, sizeof(ExteriorLights_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h index 41e567351..0ac2031af 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER GenerationDeltaTime -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_GenerationDeltaTime(const GenerationDeltaTime_t& in, cam_msgs::GenerationDeltaTime& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_GenerationDeltaTime(const cam_msgs::GenerationDeltaTime& in, GenerationDeltaTime_t& out) { - memset(&out, 0, sizeof(GenerationDeltaTime_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h index d3e97a20c..acee43990 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED HardShoulderStatus -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HardShoulderStatus(const HardShoulderStatus_t& in, cam_msgs::HardShoulderStatus& out) { - out.value = in; } void toStruct_HardShoulderStatus(const cam_msgs::HardShoulderStatus& in, HardShoulderStatus_t& out) { - memset(&out, 0, sizeof(HardShoulderStatus_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 0e9e4cbe6..0eca0d2aa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationAnimalOnTheRoadSubCauseCode(const HazardousLocation_AnimalOnTheRoadSubCauseCode_t& in, cam_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationAnimalOnTheRoadSubCauseCode(const cam_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& in, HazardousLocation_AnimalOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_AnimalOnTheRoadSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index 43b81b7d5..e57593598 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationDangerousCurveSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationDangerousCurveSubCauseCode(const HazardousLocation_DangerousCurveSubCauseCode_t& in, cam_msgs::HazardousLocationDangerousCurveSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationDangerousCurveSubCauseCode(const cam_msgs::HazardousLocationDangerousCurveSubCauseCode& in, HazardousLocation_DangerousCurveSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_DangerousCurveSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index 4e9016370..b8b58e45c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationObstacleOnTheRoadSubCauseCode(const HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& in, cam_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationObstacleOnTheRoadSubCauseCode(const cam_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& in, HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_ObstacleOnTheRoadSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 8f828c378..014e5752a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationSurfaceConditionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationSurfaceConditionSubCauseCode(const HazardousLocation_SurfaceConditionSubCauseCode_t& in, cam_msgs::HazardousLocationSurfaceConditionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationSurfaceConditionSubCauseCode(const cam_msgs::HazardousLocationSurfaceConditionSubCauseCode& in, HazardousLocation_SurfaceConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_SurfaceConditionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index caea1f550..4d44b337b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Heading -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Heading(const Heading_t& in, cam_msgs::Heading& out) { - toRos_HeadingValue(in.headingValue, out.heading_value); toRos_HeadingConfidence(in.headingConfidence, out.heading_confidence); } void toStruct_Heading(const cam_msgs::Heading& in, Heading_t& out) { - memset(&out, 0, sizeof(Heading_t)); toStruct_HeadingValue(in.heading_value, out.headingValue); toStruct_HeadingConfidence(in.heading_confidence, out.headingConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h index d5db41c8d..98289f46f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HeadingConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HeadingConfidence(const HeadingConfidence_t& in, cam_msgs::HeadingConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingConfidence(const cam_msgs::HeadingConfidence& in, HeadingConfidence_t& out) { - memset(&out, 0, sizeof(HeadingConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h index 06e9b1054..95400c78b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HeadingValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HeadingValue(const HeadingValue_t& in, cam_msgs::HeadingValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingValue(const cam_msgs::HeadingValue& in, HeadingValue_t& out) { - memset(&out, 0, sizeof(HeadingValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h index a0f89ca1d..fdbaa2d03 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HeightLonCarr -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HeightLonCarr(const HeightLonCarr_t& in, cam_msgs::HeightLonCarr& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeightLonCarr(const cam_msgs::HeightLonCarr& in, HeightLonCarr_t& out) { - memset(&out, 0, sizeof(HeightLonCarr_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h index 9a942860a..bca1c1c56 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// CHOICE HighFrequencyContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,32 +20,33 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HighFrequencyContainer(const HighFrequencyContainer_t& in, cam_msgs::HighFrequencyContainer& out) { - - if (in.present == HighFrequencyContainer_PR::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency) { + switch (in.present) { + case HighFrequencyContainer_PR_basicVehicleContainerHighFrequency: toRos_BasicVehicleContainerHighFrequency(in.choice.basicVehicleContainerHighFrequency, out.basic_vehicle_container_high_frequency); out.choice = cam_msgs::HighFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY; - } - - if (in.present == HighFrequencyContainer_PR::HighFrequencyContainer_PR_rsuContainerHighFrequency) { + break; + case HighFrequencyContainer_PR_rsuContainerHighFrequency: toRos_RSUContainerHighFrequency(in.choice.rsuContainerHighFrequency, out.rsu_container_high_frequency); out.choice = cam_msgs::HighFrequencyContainer::CHOICE_RSU_CONTAINER_HIGH_FREQUENCY; + break; + default: break; } } void toStruct_HighFrequencyContainer(const cam_msgs::HighFrequencyContainer& in, HighFrequencyContainer_t& out) { - memset(&out, 0, sizeof(HighFrequencyContainer_t)); - if (in.choice == cam_msgs::HighFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY) { + switch (in.choice) { + case cam_msgs::HighFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY: toStruct_BasicVehicleContainerHighFrequency(in.basic_vehicle_container_high_frequency, out.choice.basicVehicleContainerHighFrequency); out.present = HighFrequencyContainer_PR::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency; - } - - if (in.choice == cam_msgs::HighFrequencyContainer::CHOICE_RSU_CONTAINER_HIGH_FREQUENCY) { + break; + case cam_msgs::HighFrequencyContainer::CHOICE_RSU_CONTAINER_HIGH_FREQUENCY: toStruct_RSUContainerHighFrequency(in.rsu_container_high_frequency, out.choice.rsuContainerHighFrequency); out.present = HighFrequencyContainer_PR::HighFrequencyContainer_PR_rsuContainerHighFrequency; + break; + default: break; } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index 3a223f984..0efea238c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HumanPresenceOnTheRoadSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HumanPresenceOnTheRoadSubCauseCode(const HumanPresenceOnTheRoadSubCauseCode_t& in, cam_msgs::HumanPresenceOnTheRoadSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanPresenceOnTheRoadSubCauseCode(const cam_msgs::HumanPresenceOnTheRoadSubCauseCode& in, HumanPresenceOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanPresenceOnTheRoadSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h index d97aaa8c8..406ae6724 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HumanProblemSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HumanProblemSubCauseCode(const HumanProblemSubCauseCode_t& in, cam_msgs::HumanProblemSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanProblemSubCauseCode(const cam_msgs::HumanProblemSubCauseCode& in, HumanProblemSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanProblemSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h index 744fadf76..c2bc19d8f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER InformationQuality -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_InformationQuality(const InformationQuality_t& in, cam_msgs::InformationQuality& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_InformationQuality(const cam_msgs::InformationQuality& in, InformationQuality_t& out) { - memset(&out, 0, sizeof(InformationQuality_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h index d63d0779a..e17895882 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF ItineraryPath -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ItineraryPath(const ItineraryPath_t& in, cam_msgs::ItineraryPath& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::ReferencePosition array; - toRos_ReferencePosition(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::ReferencePosition el; + toRos_ReferencePosition(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_ItineraryPath(const cam_msgs::ItineraryPath& in, ItineraryPath_t& out) { - memset(&out, 0, sizeof(ItineraryPath_t)); - for (int i = 0; i < in.array.size(); i++) { - ReferencePosition_t array; - toStruct_ReferencePosition(in.array[i], array); - ReferencePosition_t* array_ptr = new ReferencePosition_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); + toStruct_ReferencePosition(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h index 22bc2dbcc..3b915c33d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h @@ -1,33 +1,14 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ItsPduHeader -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include +#include #include +#include #include #include #ifdef ROS1 @@ -42,14 +23,12 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ItsPduHeader(const ItsPduHeader_t& in, cam_msgs::ItsPduHeader& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in.protocolVersion, out.protocol_version); etsi_its_primitives_conversion::toRos_INTEGER(in.messageID, out.message_id); toRos_StationID(in.stationID, out.station_id); } void toStruct_ItsPduHeader(const cam_msgs::ItsPduHeader& in, ItsPduHeader_t& out) { - memset(&out, 0, sizeof(ItsPduHeader_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.protocol_version, out.protocolVersion); @@ -57,4 +36,4 @@ void toStruct_ItsPduHeader(const cam_msgs::ItsPduHeader& in, ItsPduHeader_t& out toStruct_StationID(in.station_id, out.stationID); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h index a91fd72d3..17cdd4bc0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER LanePosition -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LanePosition(const LanePosition_t& in, cam_msgs::LanePosition& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LanePosition(const cam_msgs::LanePosition& in, LanePosition_t& out) { - memset(&out, 0, sizeof(LanePosition_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index e6ffd03f5..6246ed087 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE LateralAcceleration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LateralAcceleration(const LateralAcceleration_t& in, cam_msgs::LateralAcceleration& out) { - toRos_LateralAccelerationValue(in.lateralAccelerationValue, out.lateral_acceleration_value); toRos_AccelerationConfidence(in.lateralAccelerationConfidence, out.lateral_acceleration_confidence); } void toStruct_LateralAcceleration(const cam_msgs::LateralAcceleration& in, LateralAcceleration_t& out) { - memset(&out, 0, sizeof(LateralAcceleration_t)); toStruct_LateralAccelerationValue(in.lateral_acceleration_value, out.lateralAccelerationValue); toStruct_AccelerationConfidence(in.lateral_acceleration_confidence, out.lateralAccelerationConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h index c344993a9..9af6bfc11 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER LateralAccelerationValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LateralAccelerationValue(const LateralAccelerationValue_t& in, cam_msgs::LateralAccelerationValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LateralAccelerationValue(const cam_msgs::LateralAccelerationValue& in, LateralAccelerationValue_t& out) { - memset(&out, 0, sizeof(LateralAccelerationValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h index ab91dcc1b..8301894e4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER Latitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Latitude(const Latitude_t& in, cam_msgs::Latitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Latitude(const cam_msgs::Latitude& in, Latitude_t& out) { - memset(&out, 0, sizeof(Latitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h index c4d0682e9..e02a2fb05 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING LightBarSirenInUse -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LightBarSirenInUse(const LightBarSirenInUse_t& in, cam_msgs::LightBarSirenInUse& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_LightBarSirenInUse(const cam_msgs::LightBarSirenInUse& in, LightBarSirenInUse_t& out) { - memset(&out, 0, sizeof(LightBarSirenInUse_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h index 6caf589b0..449b745ec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER Longitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Longitude(const Longitude_t& in, cam_msgs::Longitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Longitude(const cam_msgs::Longitude& in, Longitude_t& out) { - memset(&out, 0, sizeof(Longitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h index 6bba1a608..93006fdfc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE LongitudinalAcceleration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LongitudinalAcceleration(const LongitudinalAcceleration_t& in, cam_msgs::LongitudinalAcceleration& out) { - toRos_LongitudinalAccelerationValue(in.longitudinalAccelerationValue, out.longitudinal_acceleration_value); toRos_AccelerationConfidence(in.longitudinalAccelerationConfidence, out.longitudinal_acceleration_confidence); } void toStruct_LongitudinalAcceleration(const cam_msgs::LongitudinalAcceleration& in, LongitudinalAcceleration_t& out) { - memset(&out, 0, sizeof(LongitudinalAcceleration_t)); toStruct_LongitudinalAccelerationValue(in.longitudinal_acceleration_value, out.longitudinalAccelerationValue); toStruct_AccelerationConfidence(in.longitudinal_acceleration_confidence, out.longitudinalAccelerationConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h index 1af7724de..365e97b0d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER LongitudinalAccelerationValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LongitudinalAccelerationValue(const LongitudinalAccelerationValue_t& in, cam_msgs::LongitudinalAccelerationValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LongitudinalAccelerationValue(const cam_msgs::LongitudinalAccelerationValue& in, LongitudinalAccelerationValue_t& out) { - memset(&out, 0, sizeof(LongitudinalAccelerationValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h index 4f9586ed1..facb053a1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// CHOICE LowFrequencyContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #ifdef ROS1 @@ -40,22 +19,25 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LowFrequencyContainer(const LowFrequencyContainer_t& in, cam_msgs::LowFrequencyContainer& out) { - - if (in.present == LowFrequencyContainer_PR::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency) { + switch (in.present) { + case LowFrequencyContainer_PR_basicVehicleContainerLowFrequency: toRos_BasicVehicleContainerLowFrequency(in.choice.basicVehicleContainerLowFrequency, out.basic_vehicle_container_low_frequency); out.choice = cam_msgs::LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY; + break; + default: break; } } void toStruct_LowFrequencyContainer(const cam_msgs::LowFrequencyContainer& in, LowFrequencyContainer_t& out) { - memset(&out, 0, sizeof(LowFrequencyContainer_t)); - if (in.choice == cam_msgs::LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY) { + switch (in.choice) { + case cam_msgs::LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY: toStruct_BasicVehicleContainerLowFrequency(in.basic_vehicle_container_low_frequency, out.choice.basicVehicleContainerLowFrequency); out.present = LowFrequencyContainer_PR::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency; + break; + default: break; } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h index d8c0a6dea..2505897b9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER NumberOfOccupants -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_NumberOfOccupants(const NumberOfOccupants_t& in, cam_msgs::NumberOfOccupants& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_NumberOfOccupants(const cam_msgs::NumberOfOccupants& in, NumberOfOccupants_t& out) { - memset(&out, 0, sizeof(NumberOfOccupants_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h index d3abe0aec..21d5da81c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// UTF8String OpeningDaysHours -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_OpeningDaysHours(const OpeningDaysHours_t& in, cam_msgs::OpeningDaysHours& out) { - etsi_its_primitives_conversion::toRos_UTF8String(in, out.value); } void toStruct_OpeningDaysHours(const cam_msgs::OpeningDaysHours& in, OpeningDaysHours_t& out) { - memset(&out, 0, sizeof(OpeningDaysHours_t)); + etsi_its_primitives_conversion::toStruct_UTF8String(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h index 4093721f0..41ff920fe 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PathDeltaTime -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PathDeltaTime(const PathDeltaTime_t& in, cam_msgs::PathDeltaTime& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PathDeltaTime(const cam_msgs::PathDeltaTime& in, PathDeltaTime_t& out) { - memset(&out, 0, sizeof(PathDeltaTime_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h index bfe8ec960..22133d938 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF PathHistory -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PathHistory(const PathHistory_t& in, cam_msgs::PathHistory& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::PathPoint array; - toRos_PathPoint(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::PathPoint el; + toRos_PathPoint(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_PathHistory(const cam_msgs::PathHistory& in, PathHistory_t& out) { - memset(&out, 0, sizeof(PathHistory_t)); - for (int i = 0; i < in.array.size(); i++) { - PathPoint_t array; - toStruct_PathPoint(in.array[i], array); - PathPoint_t* array_ptr = new PathPoint_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + PathPoint_t* el = (PathPoint_t*) calloc(1, sizeof(PathPoint_t)); + toStruct_PathPoint(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index f81dd2571..83c96ecc4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PathPoint -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,26 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PathPoint(const PathPoint_t& in, cam_msgs::PathPoint& out) { - toRos_DeltaReferencePosition(in.pathPosition, out.path_position); if (in.pathDeltaTime) { toRos_PathDeltaTime(*in.pathDeltaTime, out.path_delta_time); out.path_delta_time_is_present = true; } - } void toStruct_PathPoint(const cam_msgs::PathPoint& in, PathPoint_t& out) { - memset(&out, 0, sizeof(PathPoint_t)); toStruct_DeltaReferencePosition(in.path_position, out.pathPosition); if (in.path_delta_time_is_present) { - PathDeltaTime_t path_delta_time; - toStruct_PathDeltaTime(in.path_delta_time, path_delta_time); - out.pathDeltaTime = new PathDeltaTime_t(path_delta_time); + out.pathDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); + toStruct_PathDeltaTime(in.path_delta_time, *out.pathDeltaTime); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h index 02e164d52..13b7a8e18 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PerformanceClass -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PerformanceClass(const PerformanceClass_t& in, cam_msgs::PerformanceClass& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PerformanceClass(const cam_msgs::PerformanceClass& in, PerformanceClass_t& out) { - memset(&out, 0, sizeof(PerformanceClass_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h index 47287baac..9594e2dea 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// NumericString PhoneNumber -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PhoneNumber(const PhoneNumber_t& in, cam_msgs::PhoneNumber& out) { - etsi_its_primitives_conversion::toRos_NumericString(in, out.value); } void toStruct_PhoneNumber(const cam_msgs::PhoneNumber& in, PhoneNumber_t& out) { - memset(&out, 0, sizeof(PhoneNumber_t)); + etsi_its_primitives_conversion::toStruct_NumericString(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h index 634095c68..d5fcbf1d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosCentMass -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosCentMass(const PosCentMass_t& in, cam_msgs::PosCentMass& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosCentMass(const cam_msgs::PosCentMass& in, PosCentMass_t& out) { - memset(&out, 0, sizeof(PosCentMass_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index beae50a76..5bbe13e17 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PosConfidenceEllipse -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,14 +21,12 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosConfidenceEllipse(const PosConfidenceEllipse_t& in, cam_msgs::PosConfidenceEllipse& out) { - toRos_SemiAxisLength(in.semiMajorConfidence, out.semi_major_confidence); toRos_SemiAxisLength(in.semiMinorConfidence, out.semi_minor_confidence); toRos_HeadingValue(in.semiMajorOrientation, out.semi_major_orientation); } void toStruct_PosConfidenceEllipse(const cam_msgs::PosConfidenceEllipse& in, PosConfidenceEllipse_t& out) { - memset(&out, 0, sizeof(PosConfidenceEllipse_t)); toStruct_SemiAxisLength(in.semi_major_confidence, out.semiMajorConfidence); @@ -57,4 +34,4 @@ void toStruct_PosConfidenceEllipse(const cam_msgs::PosConfidenceEllipse& in, Pos toStruct_HeadingValue(in.semi_major_orientation, out.semiMajorOrientation); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h index f93562bc5..186238114 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosFrontAx -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosFrontAx(const PosFrontAx_t& in, cam_msgs::PosFrontAx& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosFrontAx(const cam_msgs::PosFrontAx& in, PosFrontAx_t& out) { - memset(&out, 0, sizeof(PosFrontAx_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h index fba545286..4c5c6512f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosLonCarr -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosLonCarr(const PosLonCarr_t& in, cam_msgs::PosLonCarr& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosLonCarr(const cam_msgs::PosLonCarr& in, PosLonCarr_t& out) { - memset(&out, 0, sizeof(PosLonCarr_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h index 665595029..b5dc50feb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosPillar -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosPillar(const PosPillar_t& in, cam_msgs::PosPillar& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosPillar(const cam_msgs::PosPillar& in, PosPillar_t& out) { - memset(&out, 0, sizeof(PosPillar_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h index 9c58fea75..56a2019ce 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING PositionOfOccupants -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PositionOfOccupants(const PositionOfOccupants_t& in, cam_msgs::PositionOfOccupants& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_PositionOfOccupants(const cam_msgs::PositionOfOccupants& in, PositionOfOccupants_t& out) { - memset(&out, 0, sizeof(PositionOfOccupants_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 9180d5e55..d3f91c7b7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF PositionOfPillars -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PositionOfPillars(const PositionOfPillars_t& in, cam_msgs::PositionOfPillars& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::PosPillar array; - toRos_PosPillar(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::PosPillar el; + toRos_PosPillar(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_PositionOfPillars(const cam_msgs::PositionOfPillars& in, PositionOfPillars_t& out) { - memset(&out, 0, sizeof(PositionOfPillars_t)); - for (int i = 0; i < in.array.size(); i++) { - PosPillar_t array; - toStruct_PosPillar(in.array[i], array); - PosPillar_t* array_ptr = new PosPillar_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + PosPillar_t* el = (PosPillar_t*) calloc(1, sizeof(PosPillar_t)); + toStruct_PosPillar(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h index 9161dae3c..29851247d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED PositioningSolutionType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PositioningSolutionType(const PositioningSolutionType_t& in, cam_msgs::PositioningSolutionType& out) { - out.value = in; } void toStruct_PositioningSolutionType(const cam_msgs::PositioningSolutionType& in, PositioningSolutionType_t& out) { - memset(&out, 0, sizeof(PositioningSolutionType_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h index 872638dfc..daa1db40e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PostCrashSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PostCrashSubCauseCode(const PostCrashSubCauseCode_t& in, cam_msgs::PostCrashSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PostCrashSubCauseCode(const cam_msgs::PostCrashSubCauseCode& in, PostCrashSubCauseCode_t& out) { - memset(&out, 0, sizeof(PostCrashSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index 2fffe65b6..c6e5e49a3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ProtectedCommunicationZone -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -45,52 +24,41 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedCommunicationZone(const ProtectedCommunicationZone_t& in, cam_msgs::ProtectedCommunicationZone& out) { - toRos_ProtectedZoneType(in.protectedZoneType, out.protected_zone_type); if (in.expiryTime) { toRos_TimestampIts(*in.expiryTime, out.expiry_time); out.expiry_time_is_present = true; } - toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.protectedZoneRadius) { toRos_ProtectedZoneRadius(*in.protectedZoneRadius, out.protected_zone_radius); out.protected_zone_radius_is_present = true; } - if (in.protectedZoneID) { toRos_ProtectedZoneID(*in.protectedZoneID, out.protected_zone_id); out.protected_zone_id_is_present = true; } - } void toStruct_ProtectedCommunicationZone(const cam_msgs::ProtectedCommunicationZone& in, ProtectedCommunicationZone_t& out) { - memset(&out, 0, sizeof(ProtectedCommunicationZone_t)); toStruct_ProtectedZoneType(in.protected_zone_type, out.protectedZoneType); if (in.expiry_time_is_present) { - TimestampIts_t expiry_time; - toStruct_TimestampIts(in.expiry_time, expiry_time); - out.expiryTime = new TimestampIts_t(expiry_time); + out.expiryTime = (TimestampIts_t*) calloc(1, sizeof(TimestampIts_t)); + toStruct_TimestampIts(in.expiry_time, *out.expiryTime); } - toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.protected_zone_radius_is_present) { - ProtectedZoneRadius_t protected_zone_radius; - toStruct_ProtectedZoneRadius(in.protected_zone_radius, protected_zone_radius); - out.protectedZoneRadius = new ProtectedZoneRadius_t(protected_zone_radius); + out.protectedZoneRadius = (ProtectedZoneRadius_t*) calloc(1, sizeof(ProtectedZoneRadius_t)); + toStruct_ProtectedZoneRadius(in.protected_zone_radius, *out.protectedZoneRadius); } - if (in.protected_zone_id_is_present) { - ProtectedZoneID_t protected_zone_id; - toStruct_ProtectedZoneID(in.protected_zone_id, protected_zone_id); - out.protectedZoneID = new ProtectedZoneID_t(protected_zone_id); + out.protectedZoneID = (ProtectedZoneID_t*) calloc(1, sizeof(ProtectedZoneID_t)); + toStruct_ProtectedZoneID(in.protected_zone_id, *out.protectedZoneID); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index 69d223925..9e0ad6935 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF ProtectedCommunicationZonesRSU -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedCommunicationZonesRSU(const ProtectedCommunicationZonesRSU_t& in, cam_msgs::ProtectedCommunicationZonesRSU& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::ProtectedCommunicationZone array; - toRos_ProtectedCommunicationZone(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::ProtectedCommunicationZone el; + toRos_ProtectedCommunicationZone(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_ProtectedCommunicationZonesRSU(const cam_msgs::ProtectedCommunicationZonesRSU& in, ProtectedCommunicationZonesRSU_t& out) { - memset(&out, 0, sizeof(ProtectedCommunicationZonesRSU_t)); - for (int i = 0; i < in.array.size(); i++) { - ProtectedCommunicationZone_t array; - toStruct_ProtectedCommunicationZone(in.array[i], array); - ProtectedCommunicationZone_t* array_ptr = new ProtectedCommunicationZone_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ProtectedCommunicationZone_t* el = (ProtectedCommunicationZone_t*) calloc(1, sizeof(ProtectedCommunicationZone_t)); + toStruct_ProtectedCommunicationZone(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h index b675234a2..132294e25 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER ProtectedZoneID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedZoneID(const ProtectedZoneID_t& in, cam_msgs::ProtectedZoneID& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneID(const cam_msgs::ProtectedZoneID& in, ProtectedZoneID_t& out) { - memset(&out, 0, sizeof(ProtectedZoneID_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h index a385b10fc..9dec6d7d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER ProtectedZoneRadius -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedZoneRadius(const ProtectedZoneRadius_t& in, cam_msgs::ProtectedZoneRadius& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneRadius(const cam_msgs::ProtectedZoneRadius& in, ProtectedZoneRadius_t& out) { - memset(&out, 0, sizeof(ProtectedZoneRadius_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h index 71fda1286..5b3d0d18a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED ProtectedZoneType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedZoneType(const ProtectedZoneType_t& in, cam_msgs::ProtectedZoneType& out) { - out.value = in; } void toStruct_ProtectedZoneType(const cam_msgs::ProtectedZoneType& in, ProtectedZoneType_t& out) { - memset(&out, 0, sizeof(ProtectedZoneType_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index 25cbe5eb8..34f110383 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PtActivation -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PtActivation(const PtActivation_t& in, cam_msgs::PtActivation& out) { - toRos_PtActivationType(in.ptActivationType, out.pt_activation_type); toRos_PtActivationData(in.ptActivationData, out.pt_activation_data); } void toStruct_PtActivation(const cam_msgs::PtActivation& in, PtActivation_t& out) { - memset(&out, 0, sizeof(PtActivation_t)); toStruct_PtActivationType(in.pt_activation_type, out.ptActivationType); toStruct_PtActivationData(in.pt_activation_data, out.ptActivationData); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h index 11588d133..63c38ab89 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// OCTET-STRING PtActivationData -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PtActivationData(const PtActivationData_t& in, cam_msgs::PtActivationData& out) { - etsi_its_primitives_conversion::toRos_OCTET_STRING(in, out.value); } void toStruct_PtActivationData(const cam_msgs::PtActivationData& in, PtActivationData_t& out) { - memset(&out, 0, sizeof(PtActivationData_t)); + etsi_its_primitives_conversion::toStruct_OCTET_STRING(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h index 68d09fae1..eb99048d8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PtActivationType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PtActivationType(const PtActivationType_t& in, cam_msgs::PtActivationType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PtActivationType(const cam_msgs::PtActivationType& in, PtActivationType_t& out) { - memset(&out, 0, sizeof(PtActivationType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index c06b93080..0da0e3113 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PublicTransportContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,26 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PublicTransportContainer(const PublicTransportContainer_t& in, cam_msgs::PublicTransportContainer& out) { - toRos_EmbarkationStatus(in.embarkationStatus, out.embarkation_status); if (in.ptActivation) { toRos_PtActivation(*in.ptActivation, out.pt_activation); out.pt_activation_is_present = true; } - } void toStruct_PublicTransportContainer(const cam_msgs::PublicTransportContainer& in, PublicTransportContainer_t& out) { - memset(&out, 0, sizeof(PublicTransportContainer_t)); toStruct_EmbarkationStatus(in.embarkation_status, out.embarkationStatus); if (in.pt_activation_is_present) { - PtActivation_t pt_activation; - toStruct_PtActivation(in.pt_activation, pt_activation); - out.ptActivation = new PtActivation_t(pt_activation); + out.ptActivation = (PtActivation_t*) calloc(1, sizeof(PtActivation_t)); + toStruct_PtActivation(in.pt_activation, *out.ptActivation); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h index 93f4f6db8..bb58ec061 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE RSUContainerHighFrequency -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #ifdef ROS1 @@ -40,24 +19,19 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RSUContainerHighFrequency(const RSUContainerHighFrequency_t& in, cam_msgs::RSUContainerHighFrequency& out) { - if (in.protectedCommunicationZonesRSU) { toRos_ProtectedCommunicationZonesRSU(*in.protectedCommunicationZonesRSU, out.protected_communication_zones_rsu); out.protected_communication_zones_rsu_is_present = true; } - } void toStruct_RSUContainerHighFrequency(const cam_msgs::RSUContainerHighFrequency& in, RSUContainerHighFrequency_t& out) { - memset(&out, 0, sizeof(RSUContainerHighFrequency_t)); if (in.protected_communication_zones_rsu_is_present) { - ProtectedCommunicationZonesRSU_t protected_communication_zones_rsu; - toStruct_ProtectedCommunicationZonesRSU(in.protected_communication_zones_rsu, protected_communication_zones_rsu); - out.protectedCommunicationZonesRSU = new ProtectedCommunicationZonesRSU_t(protected_communication_zones_rsu); + out.protectedCommunicationZonesRSU = (ProtectedCommunicationZonesRSU_t*) calloc(1, sizeof(ProtectedCommunicationZonesRSU_t)); + toStruct_ProtectedCommunicationZonesRSU(in.protected_communication_zones_rsu, *out.protectedCommunicationZonesRSU); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index c3dce3d24..5be307ff3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ReferencePosition -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,7 +22,6 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ReferencePosition(const ReferencePosition_t& in, cam_msgs::ReferencePosition& out) { - toRos_Latitude(in.latitude, out.latitude); toRos_Longitude(in.longitude, out.longitude); toRos_PosConfidenceEllipse(in.positionConfidenceEllipse, out.position_confidence_ellipse); @@ -51,7 +29,6 @@ void toRos_ReferencePosition(const ReferencePosition_t& in, cam_msgs::ReferenceP } void toStruct_ReferencePosition(const cam_msgs::ReferencePosition& in, ReferencePosition_t& out) { - memset(&out, 0, sizeof(ReferencePosition_t)); toStruct_Latitude(in.latitude, out.latitude); @@ -60,4 +37,4 @@ void toStruct_ReferencePosition(const cam_msgs::ReferencePosition& in, Reference toStruct_Altitude(in.altitude, out.altitude); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h index 33b05e423..c57c6feaa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RelevanceDistance -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RelevanceDistance(const RelevanceDistance_t& in, cam_msgs::RelevanceDistance& out) { - out.value = in; } void toStruct_RelevanceDistance(const cam_msgs::RelevanceDistance& in, RelevanceDistance_t& out) { - memset(&out, 0, sizeof(RelevanceDistance_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h index cc52bd9f6..79075d231 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RelevanceTrafficDirection -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RelevanceTrafficDirection(const RelevanceTrafficDirection_t& in, cam_msgs::RelevanceTrafficDirection& out) { - out.value = in; } void toStruct_RelevanceTrafficDirection(const cam_msgs::RelevanceTrafficDirection& in, RelevanceTrafficDirection_t& out) { - memset(&out, 0, sizeof(RelevanceTrafficDirection_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h index b999a9457..379a7a378 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RequestResponseIndication -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RequestResponseIndication(const RequestResponseIndication_t& in, cam_msgs::RequestResponseIndication& out) { - out.value = in; } void toStruct_RequestResponseIndication(const cam_msgs::RequestResponseIndication& in, RequestResponseIndication_t& out) { - memset(&out, 0, sizeof(RequestResponseIndication_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index 190dfecfd..fb8343d69 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER RescueAndRecoveryWorkInProgressSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RescueAndRecoveryWorkInProgressSubCauseCode(const RescueAndRecoveryWorkInProgressSubCauseCode_t& in, cam_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RescueAndRecoveryWorkInProgressSubCauseCode(const cam_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& in, RescueAndRecoveryWorkInProgressSubCauseCode_t& out) { - memset(&out, 0, sizeof(RescueAndRecoveryWorkInProgressSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h index 543cd5a82..4cfb1991b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE RescueContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #ifdef ROS1 @@ -40,15 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RescueContainer(const RescueContainer_t& in, cam_msgs::RescueContainer& out) { - toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); } void toStruct_RescueContainer(const cam_msgs::RescueContainer& in, RescueContainer_t& out) { - memset(&out, 0, sizeof(RescueContainer_t)); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index 144ef7723..49b59aa48 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF RestrictedTypes -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RestrictedTypes(const RestrictedTypes_t& in, cam_msgs::RestrictedTypes& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::StationType array; - toRos_StationType(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::StationType el; + toRos_StationType(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_RestrictedTypes(const cam_msgs::RestrictedTypes& in, RestrictedTypes_t& out) { - memset(&out, 0, sizeof(RestrictedTypes_t)); - for (int i = 0; i < in.array.size(); i++) { - StationType_t array; - toStruct_StationType(in.array[i], array); - StationType_t* array_ptr = new StationType_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + StationType_t* el = (StationType_t*) calloc(1, sizeof(StationType_t)); + toStruct_StationType(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h index 8e6e7c95e..93885f497 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RoadType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RoadType(const RoadType_t& in, cam_msgs::RoadType& out) { - out.value = in; } void toStruct_RoadType(const cam_msgs::RoadType& in, RoadType_t& out) { - memset(&out, 0, sizeof(RoadType_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index ed41f19c0..a23182f36 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE RoadWorksContainerBasic -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,37 +21,29 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RoadWorksContainerBasic(const RoadWorksContainerBasic_t& in, cam_msgs::RoadWorksContainerBasic& out) { - if (in.roadworksSubCauseCode) { toRos_RoadworksSubCauseCode(*in.roadworksSubCauseCode, out.roadworks_sub_cause_code); out.roadworks_sub_cause_code_is_present = true; } - toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); if (in.closedLanes) { toRos_ClosedLanes(*in.closedLanes, out.closed_lanes); out.closed_lanes_is_present = true; } - } void toStruct_RoadWorksContainerBasic(const cam_msgs::RoadWorksContainerBasic& in, RoadWorksContainerBasic_t& out) { - memset(&out, 0, sizeof(RoadWorksContainerBasic_t)); if (in.roadworks_sub_cause_code_is_present) { - RoadworksSubCauseCode_t roadworks_sub_cause_code; - toStruct_RoadworksSubCauseCode(in.roadworks_sub_cause_code, roadworks_sub_cause_code); - out.roadworksSubCauseCode = new RoadworksSubCauseCode_t(roadworks_sub_cause_code); + out.roadworksSubCauseCode = (RoadworksSubCauseCode_t*) calloc(1, sizeof(RoadworksSubCauseCode_t)); + toStruct_RoadworksSubCauseCode(in.roadworks_sub_cause_code, *out.roadworksSubCauseCode); } - toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); if (in.closed_lanes_is_present) { - ClosedLanes_t closed_lanes; - toStruct_ClosedLanes(in.closed_lanes, closed_lanes); - out.closedLanes = new ClosedLanes_t(closed_lanes); + out.closedLanes = (ClosedLanes_t*) calloc(1, sizeof(ClosedLanes_t)); + toStruct_ClosedLanes(in.closed_lanes, *out.closedLanes); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h index d19dca4e4..196c06866 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER RoadworksSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RoadworksSubCauseCode(const RoadworksSubCauseCode_t& in, cam_msgs::RoadworksSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RoadworksSubCauseCode(const cam_msgs::RoadworksSubCauseCode& in, RoadworksSubCauseCode_t& out) { - memset(&out, 0, sizeof(RoadworksSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index 1f081af63..c031f52c4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE SafetyCarContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,48 +22,37 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SafetyCarContainer(const SafetyCarContainer_t& in, cam_msgs::SafetyCarContainer& out) { - toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); if (in.incidentIndication) { toRos_CauseCode(*in.incidentIndication, out.incident_indication); out.incident_indication_is_present = true; } - if (in.trafficRule) { toRos_TrafficRule(*in.trafficRule, out.traffic_rule); out.traffic_rule_is_present = true; } - if (in.speedLimit) { toRos_SpeedLimit(*in.speedLimit, out.speed_limit); out.speed_limit_is_present = true; } - } void toStruct_SafetyCarContainer(const cam_msgs::SafetyCarContainer& in, SafetyCarContainer_t& out) { - memset(&out, 0, sizeof(SafetyCarContainer_t)); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); if (in.incident_indication_is_present) { - CauseCode_t incident_indication; - toStruct_CauseCode(in.incident_indication, incident_indication); - out.incidentIndication = new CauseCode_t(incident_indication); + out.incidentIndication = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); + toStruct_CauseCode(in.incident_indication, *out.incidentIndication); } - if (in.traffic_rule_is_present) { - TrafficRule_t traffic_rule; - toStruct_TrafficRule(in.traffic_rule, traffic_rule); - out.trafficRule = new TrafficRule_t(traffic_rule); + out.trafficRule = (TrafficRule_t*) calloc(1, sizeof(TrafficRule_t)); + toStruct_TrafficRule(in.traffic_rule, *out.trafficRule); } - if (in.speed_limit_is_present) { - SpeedLimit_t speed_limit; - toStruct_SpeedLimit(in.speed_limit, speed_limit); - out.speedLimit = new SpeedLimit_t(speed_limit); + out.speedLimit = (SpeedLimit_t*) calloc(1, sizeof(SpeedLimit_t)); + toStruct_SpeedLimit(in.speed_limit, *out.speedLimit); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h index 12fce5fd1..4862cc6da 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SemiAxisLength -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SemiAxisLength(const SemiAxisLength_t& in, cam_msgs::SemiAxisLength& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SemiAxisLength(const cam_msgs::SemiAxisLength& in, SemiAxisLength_t& out) { - memset(&out, 0, sizeof(SemiAxisLength_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h index d81a019ea..8412c3361 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SequenceNumber -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SequenceNumber(const SequenceNumber_t& in, cam_msgs::SequenceNumber& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SequenceNumber(const cam_msgs::SequenceNumber& in, SequenceNumber_t& out) { - memset(&out, 0, sizeof(SequenceNumber_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h index 468179bd3..a455af8cb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SignalViolationSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SignalViolationSubCauseCode(const SignalViolationSubCauseCode_t& in, cam_msgs::SignalViolationSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SignalViolationSubCauseCode(const cam_msgs::SignalViolationSubCauseCode& in, SignalViolationSubCauseCode_t& out) { - memset(&out, 0, sizeof(SignalViolationSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h index 7403604ce..03644fb8d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SlowVehicleSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SlowVehicleSubCauseCode(const SlowVehicleSubCauseCode_t& in, cam_msgs::SlowVehicleSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SlowVehicleSubCauseCode(const cam_msgs::SlowVehicleSubCauseCode& in, SlowVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(SlowVehicleSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h index ad068765c..2187f4e09 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE SpecialTransportContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpecialTransportContainer(const SpecialTransportContainer_t& in, cam_msgs::SpecialTransportContainer& out) { - toRos_SpecialTransportType(in.specialTransportType, out.special_transport_type); toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); } void toStruct_SpecialTransportContainer(const cam_msgs::SpecialTransportContainer& in, SpecialTransportContainer_t& out) { - memset(&out, 0, sizeof(SpecialTransportContainer_t)); toStruct_SpecialTransportType(in.special_transport_type, out.specialTransportType); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h index 4c4444634..49d709836 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING SpecialTransportType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpecialTransportType(const SpecialTransportType_t& in, cam_msgs::SpecialTransportType& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_SpecialTransportType(const cam_msgs::SpecialTransportType& in, SpecialTransportType_t& out) { - memset(&out, 0, sizeof(SpecialTransportType_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index 6ebd44506..5d6242e21 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// CHOICE SpecialVehicleContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -46,82 +25,73 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpecialVehicleContainer(const SpecialVehicleContainer_t& in, cam_msgs::SpecialVehicleContainer& out) { - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_publicTransportContainer) { + switch (in.present) { + case SpecialVehicleContainer_PR_publicTransportContainer: toRos_PublicTransportContainer(in.choice.publicTransportContainer, out.public_transport_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_PUBLIC_TRANSPORT_CONTAINER; - } - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_specialTransportContainer) { + break; + case SpecialVehicleContainer_PR_specialTransportContainer: toRos_SpecialTransportContainer(in.choice.specialTransportContainer, out.special_transport_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_SPECIAL_TRANSPORT_CONTAINER; - } - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_dangerousGoodsContainer) { + break; + case SpecialVehicleContainer_PR_dangerousGoodsContainer: toRos_DangerousGoodsContainer(in.choice.dangerousGoodsContainer, out.dangerous_goods_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_DANGEROUS_GOODS_CONTAINER; - } - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_roadWorksContainerBasic) { + break; + case SpecialVehicleContainer_PR_roadWorksContainerBasic: toRos_RoadWorksContainerBasic(in.choice.roadWorksContainerBasic, out.road_works_container_basic); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_ROAD_WORKS_CONTAINER_BASIC; - } - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_rescueContainer) { + break; + case SpecialVehicleContainer_PR_rescueContainer: toRos_RescueContainer(in.choice.rescueContainer, out.rescue_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_RESCUE_CONTAINER; - } - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_emergencyContainer) { + break; + case SpecialVehicleContainer_PR_emergencyContainer: toRos_EmergencyContainer(in.choice.emergencyContainer, out.emergency_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_EMERGENCY_CONTAINER; - } - - if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_safetyCarContainer) { + break; + case SpecialVehicleContainer_PR_safetyCarContainer: toRos_SafetyCarContainer(in.choice.safetyCarContainer, out.safety_car_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_SAFETY_CAR_CONTAINER; + break; + default: break; } } void toStruct_SpecialVehicleContainer(const cam_msgs::SpecialVehicleContainer& in, SpecialVehicleContainer_t& out) { - memset(&out, 0, sizeof(SpecialVehicleContainer_t)); - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_PUBLIC_TRANSPORT_CONTAINER) { + switch (in.choice) { + case cam_msgs::SpecialVehicleContainer::CHOICE_PUBLIC_TRANSPORT_CONTAINER: toStruct_PublicTransportContainer(in.public_transport_container, out.choice.publicTransportContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_publicTransportContainer; - } - - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_SPECIAL_TRANSPORT_CONTAINER) { + break; + case cam_msgs::SpecialVehicleContainer::CHOICE_SPECIAL_TRANSPORT_CONTAINER: toStruct_SpecialTransportContainer(in.special_transport_container, out.choice.specialTransportContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_specialTransportContainer; - } - - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_DANGEROUS_GOODS_CONTAINER) { + break; + case cam_msgs::SpecialVehicleContainer::CHOICE_DANGEROUS_GOODS_CONTAINER: toStruct_DangerousGoodsContainer(in.dangerous_goods_container, out.choice.dangerousGoodsContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_dangerousGoodsContainer; - } - - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_ROAD_WORKS_CONTAINER_BASIC) { + break; + case cam_msgs::SpecialVehicleContainer::CHOICE_ROAD_WORKS_CONTAINER_BASIC: toStruct_RoadWorksContainerBasic(in.road_works_container_basic, out.choice.roadWorksContainerBasic); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_roadWorksContainerBasic; - } - - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_RESCUE_CONTAINER) { + break; + case cam_msgs::SpecialVehicleContainer::CHOICE_RESCUE_CONTAINER: toStruct_RescueContainer(in.rescue_container, out.choice.rescueContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_rescueContainer; - } - - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_EMERGENCY_CONTAINER) { + break; + case cam_msgs::SpecialVehicleContainer::CHOICE_EMERGENCY_CONTAINER: toStruct_EmergencyContainer(in.emergency_container, out.choice.emergencyContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_emergencyContainer; - } - - if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_SAFETY_CAR_CONTAINER) { + break; + case cam_msgs::SpecialVehicleContainer::CHOICE_SAFETY_CAR_CONTAINER: toStruct_SafetyCarContainer(in.safety_car_container, out.choice.safetyCarContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_safetyCarContainer; + break; + default: break; } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index 8c6a6ab79..ca3d31f2d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Speed -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Speed(const Speed_t& in, cam_msgs::Speed& out) { - toRos_SpeedValue(in.speedValue, out.speed_value); toRos_SpeedConfidence(in.speedConfidence, out.speed_confidence); } void toStruct_Speed(const cam_msgs::Speed& in, Speed_t& out) { - memset(&out, 0, sizeof(Speed_t)); toStruct_SpeedValue(in.speed_value, out.speedValue); toStruct_SpeedConfidence(in.speed_confidence, out.speedConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h index 6830fd601..74981ab2c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SpeedConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpeedConfidence(const SpeedConfidence_t& in, cam_msgs::SpeedConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedConfidence(const cam_msgs::SpeedConfidence& in, SpeedConfidence_t& out) { - memset(&out, 0, sizeof(SpeedConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h index 10712953e..7413358a0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SpeedLimit -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpeedLimit(const SpeedLimit_t& in, cam_msgs::SpeedLimit& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedLimit(const cam_msgs::SpeedLimit& in, SpeedLimit_t& out) { - memset(&out, 0, sizeof(SpeedLimit_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h index 82536bb4f..3bd0d34cf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SpeedValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpeedValue(const SpeedValue_t& in, cam_msgs::SpeedValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedValue(const cam_msgs::SpeedValue& in, SpeedValue_t& out) { - memset(&out, 0, sizeof(SpeedValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h index 65e0410b3..833df3d70 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER StationID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationID(const StationID_t& in, cam_msgs::StationID& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationID(const cam_msgs::StationID& in, StationID_t& out) { - memset(&out, 0, sizeof(StationID_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h index b36956ad4..61480bfe0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER StationType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationType(const StationType_t& in, cam_msgs::StationType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationType(const cam_msgs::StationType& in, StationType_t& out) { - memset(&out, 0, sizeof(StationType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h index e08a57d70..4f4847ffd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED StationarySince -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationarySince(const StationarySince_t& in, cam_msgs::StationarySince& out) { - out.value = in; } void toStruct_StationarySince(const cam_msgs::StationarySince& in, StationarySince_t& out) { - memset(&out, 0, sizeof(StationarySince_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h index 3612d7dd9..e8c9ab611 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER StationaryVehicleSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationaryVehicleSubCauseCode(const StationaryVehicleSubCauseCode_t& in, cam_msgs::StationaryVehicleSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationaryVehicleSubCauseCode(const cam_msgs::StationaryVehicleSubCauseCode& in, StationaryVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(StationaryVehicleSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index 876b41023..d765f952c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE SteeringWheelAngle -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SteeringWheelAngle(const SteeringWheelAngle_t& in, cam_msgs::SteeringWheelAngle& out) { - toRos_SteeringWheelAngleValue(in.steeringWheelAngleValue, out.steering_wheel_angle_value); toRos_SteeringWheelAngleConfidence(in.steeringWheelAngleConfidence, out.steering_wheel_angle_confidence); } void toStruct_SteeringWheelAngle(const cam_msgs::SteeringWheelAngle& in, SteeringWheelAngle_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngle_t)); toStruct_SteeringWheelAngleValue(in.steering_wheel_angle_value, out.steeringWheelAngleValue); toStruct_SteeringWheelAngleConfidence(in.steering_wheel_angle_confidence, out.steeringWheelAngleConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h index 0971a23df..89c463006 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SteeringWheelAngleConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SteeringWheelAngleConfidence(const SteeringWheelAngleConfidence_t& in, cam_msgs::SteeringWheelAngleConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleConfidence(const cam_msgs::SteeringWheelAngleConfidence& in, SteeringWheelAngleConfidence_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h index beeb5b64f..7e7a04cdb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SteeringWheelAngleValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SteeringWheelAngleValue(const SteeringWheelAngleValue_t& in, cam_msgs::SteeringWheelAngleValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleValue(const cam_msgs::SteeringWheelAngleValue& in, SteeringWheelAngleValue_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h index 92cfb62ca..45277cdbc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SubCauseCodeType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SubCauseCodeType(const SubCauseCodeType_t& in, cam_msgs::SubCauseCodeType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SubCauseCodeType(const cam_msgs::SubCauseCodeType& in, SubCauseCodeType_t& out) { - memset(&out, 0, sizeof(SubCauseCodeType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h index 19a18da5a..f0f02aeff 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER Temperature -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Temperature(const Temperature_t& in, cam_msgs::Temperature& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Temperature(const cam_msgs::Temperature& in, Temperature_t& out) { - memset(&out, 0, sizeof(Temperature_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h index f12b36da5..dd39d6854 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TimestampIts -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TimestampIts(const TimestampIts_t& in, cam_msgs::TimestampIts& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TimestampIts(const cam_msgs::TimestampIts& in, TimestampIts_t& out) { - memset(&out, 0, sizeof(TimestampIts_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index fcaa3668c..f810e66f4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF Traces -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace cam_msgs = etsi_its_cam_msgs; #else -#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Traces(const Traces_t& in, cam_msgs::Traces& out) { - - for (int i = 0; i < in.list.count; i++) { - cam_msgs::PathHistory array; - toRos_PathHistory(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + cam_msgs::PathHistory el; + toRos_PathHistory(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_Traces(const cam_msgs::Traces& in, Traces_t& out) { - memset(&out, 0, sizeof(Traces_t)); - for (int i = 0; i < in.array.size(); i++) { - PathHistory_t array; - toStruct_PathHistory(in.array[i], array); - PathHistory_t* array_ptr = new PathHistory_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + PathHistory_t* el = (PathHistory_t*) calloc(1, sizeof(PathHistory_t)); + toStruct_PathHistory(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h index e3e82d758..f2f551f51 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TrafficConditionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TrafficConditionSubCauseCode(const TrafficConditionSubCauseCode_t& in, cam_msgs::TrafficConditionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TrafficConditionSubCauseCode(const cam_msgs::TrafficConditionSubCauseCode& in, TrafficConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(TrafficConditionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h index badd4b3be..35fceafc2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED TrafficRule -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TrafficRule(const TrafficRule_t& in, cam_msgs::TrafficRule& out) { - out.value = in; } void toStruct_TrafficRule(const cam_msgs::TrafficRule& in, TrafficRule_t& out) { - memset(&out, 0, sizeof(TrafficRule_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h index c120ee048..e4fb251e2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TransmissionInterval -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TransmissionInterval(const TransmissionInterval_t& in, cam_msgs::TransmissionInterval& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TransmissionInterval(const cam_msgs::TransmissionInterval& in, TransmissionInterval_t& out) { - memset(&out, 0, sizeof(TransmissionInterval_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h index 932813d6c..79692be4d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TurningRadius -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TurningRadius(const TurningRadius_t& in, cam_msgs::TurningRadius& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TurningRadius(const cam_msgs::TurningRadius& in, TurningRadius_t& out) { - memset(&out, 0, sizeof(TurningRadius_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h index a11c4c450..5c3378e1f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// IA5String VDS -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VDS(const VDS_t& in, cam_msgs::VDS& out) { - etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_VDS(const cam_msgs::VDS& in, VDS_t& out) { - memset(&out, 0, sizeof(VDS_t)); + etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h index a9a0bbd24..5070bf909 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER ValidityDuration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ValidityDuration(const ValidityDuration_t& in, cam_msgs::ValidityDuration& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ValidityDuration(const cam_msgs::ValidityDuration& in, ValidityDuration_t& out) { - memset(&out, 0, sizeof(ValidityDuration_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h index 9eb5fd145..9c66a2e63 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleBreakdownSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleBreakdownSubCauseCode(const VehicleBreakdownSubCauseCode_t& in, cam_msgs::VehicleBreakdownSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleBreakdownSubCauseCode(const cam_msgs::VehicleBreakdownSubCauseCode& in, VehicleBreakdownSubCauseCode_t& out) { - memset(&out, 0, sizeof(VehicleBreakdownSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index 786a6a8bc..33921da9d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE VehicleIdentification -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,35 +20,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleIdentification(const VehicleIdentification_t& in, cam_msgs::VehicleIdentification& out) { - if (in.wMInumber) { - toRos_WMInumber(*in.wMInumber, out.wm_inumber); - out.wm_inumber_is_present = true; + toRos_WMInumber(*in.wMInumber, out.w_m_inumber); + out.w_m_inumber_is_present = true; } - if (in.vDS) { - toRos_VDS(*in.vDS, out.vds); - out.vds_is_present = true; + toRos_VDS(*in.vDS, out.v_ds); + out.v_ds_is_present = true; } - } void toStruct_VehicleIdentification(const cam_msgs::VehicleIdentification& in, VehicleIdentification_t& out) { - memset(&out, 0, sizeof(VehicleIdentification_t)); - if (in.wm_inumber_is_present) { - WMInumber_t wm_inumber; - toStruct_WMInumber(in.wm_inumber, wm_inumber); - out.wMInumber = new WMInumber_t(wm_inumber); + if (in.w_m_inumber_is_present) { + out.wMInumber = (WMInumber_t*) calloc(1, sizeof(WMInumber_t)); + toStruct_WMInumber(in.w_m_inumber, *out.wMInumber); } - - if (in.vds_is_present) { - VDS_t vds; - toStruct_VDS(in.vds, vds); - out.vDS = new VDS_t(vds); + if (in.v_ds_is_present) { + out.vDS = (VDS_t*) calloc(1, sizeof(VDS_t)); + toStruct_VDS(in.v_ds, *out.vDS); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index a95466a17..4ed75c9c2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE VehicleLength -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleLength(const VehicleLength_t& in, cam_msgs::VehicleLength& out) { - toRos_VehicleLengthValue(in.vehicleLengthValue, out.vehicle_length_value); toRos_VehicleLengthConfidenceIndication(in.vehicleLengthConfidenceIndication, out.vehicle_length_confidence_indication); } void toStruct_VehicleLength(const cam_msgs::VehicleLength& in, VehicleLength_t& out) { - memset(&out, 0, sizeof(VehicleLength_t)); toStruct_VehicleLengthValue(in.vehicle_length_value, out.vehicleLengthValue); toStruct_VehicleLengthConfidenceIndication(in.vehicle_length_confidence_indication, out.vehicleLengthConfidenceIndication); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h index dbc1eed72..31e375abb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED VehicleLengthConfidenceIndication -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleLengthConfidenceIndication(const VehicleLengthConfidenceIndication_t& in, cam_msgs::VehicleLengthConfidenceIndication& out) { - out.value = in; } void toStruct_VehicleLengthConfidenceIndication(const cam_msgs::VehicleLengthConfidenceIndication& in, VehicleLengthConfidenceIndication_t& out) { - memset(&out, 0, sizeof(VehicleLengthConfidenceIndication_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h index 74afa359f..5ee3b2c0a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleLengthValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleLengthValue(const VehicleLengthValue_t& in, cam_msgs::VehicleLengthValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleLengthValue(const cam_msgs::VehicleLengthValue& in, VehicleLengthValue_t& out) { - memset(&out, 0, sizeof(VehicleLengthValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h index e51e1c924..e97468791 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleMass -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleMass(const VehicleMass_t& in, cam_msgs::VehicleMass& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleMass(const cam_msgs::VehicleMass& in, VehicleMass_t& out) { - memset(&out, 0, sizeof(VehicleMass_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h index 19bf81331..43242a4fd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED VehicleRole -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleRole(const VehicleRole_t& in, cam_msgs::VehicleRole& out) { - out.value = in; } void toStruct_VehicleRole(const cam_msgs::VehicleRole& in, VehicleRole_t& out) { - memset(&out, 0, sizeof(VehicleRole_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h index 7b9e2a904..cff25ebc9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleWidth -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleWidth(const VehicleWidth_t& in, cam_msgs::VehicleWidth& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleWidth(const cam_msgs::VehicleWidth& in, VehicleWidth_t& out) { - memset(&out, 0, sizeof(VehicleWidth_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index 68267c305..b1a1b2d52 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE VerticalAcceleration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VerticalAcceleration(const VerticalAcceleration_t& in, cam_msgs::VerticalAcceleration& out) { - toRos_VerticalAccelerationValue(in.verticalAccelerationValue, out.vertical_acceleration_value); toRos_AccelerationConfidence(in.verticalAccelerationConfidence, out.vertical_acceleration_confidence); } void toStruct_VerticalAcceleration(const cam_msgs::VerticalAcceleration& in, VerticalAcceleration_t& out) { - memset(&out, 0, sizeof(VerticalAcceleration_t)); toStruct_VerticalAccelerationValue(in.vertical_acceleration_value, out.verticalAccelerationValue); toStruct_AccelerationConfidence(in.vertical_acceleration_confidence, out.verticalAccelerationConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h index 5e74c8131..790489e15 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VerticalAccelerationValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VerticalAccelerationValue(const VerticalAccelerationValue_t& in, cam_msgs::VerticalAccelerationValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VerticalAccelerationValue(const cam_msgs::VerticalAccelerationValue& in, VerticalAccelerationValue_t& out) { - memset(&out, 0, sizeof(VerticalAccelerationValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h index 178ba1ef4..9e5728015 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// IA5String WMInumber -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_WMInumber(const WMInumber_t& in, cam_msgs::WMInumber& out) { - etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_WMInumber(const cam_msgs::WMInumber& in, WMInumber_t& out) { - memset(&out, 0, sizeof(WMInumber_t)); + etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h index f292aa1a4..0f23c2019 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER WheelBaseVehicle -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_WheelBaseVehicle(const WheelBaseVehicle_t& in, cam_msgs::WheelBaseVehicle& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WheelBaseVehicle(const cam_msgs::WheelBaseVehicle& in, WheelBaseVehicle_t& out) { - memset(&out, 0, sizeof(WheelBaseVehicle_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h index 19aeb32c9..09b08f9a1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER WrongWayDrivingSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_WrongWayDrivingSubCauseCode(const WrongWayDrivingSubCauseCode_t& in, cam_msgs::WrongWayDrivingSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WrongWayDrivingSubCauseCode(const cam_msgs::WrongWayDrivingSubCauseCode& in, WrongWayDrivingSubCauseCode_t& out) { - memset(&out, 0, sizeof(WrongWayDrivingSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index 24784a875..bdb592288 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE YawRate -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_YawRate(const YawRate_t& in, cam_msgs::YawRate& out) { - toRos_YawRateValue(in.yawRateValue, out.yaw_rate_value); toRos_YawRateConfidence(in.yawRateConfidence, out.yaw_rate_confidence); } void toStruct_YawRate(const cam_msgs::YawRate& in, YawRate_t& out) { - memset(&out, 0, sizeof(YawRate_t)); toStruct_YawRateValue(in.yaw_rate_value, out.yawRateValue); toStruct_YawRateConfidence(in.yaw_rate_confidence, out.yawRateConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h index 067f7bda8..da6677eab 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED YawRateConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -39,14 +19,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_YawRateConfidence(const YawRateConfidence_t& in, cam_msgs::YawRateConfidence& out) { - out.value = in; } void toStruct_YawRateConfidence(const cam_msgs::YawRateConfidence& in, YawRateConfidence_t& out) { - memset(&out, 0, sizeof(YawRateConfidence_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h index c6bfef717..c200ba4f3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER YawRateValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_YawRateValue(const YawRateValue_t& in, cam_msgs::YawRateValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_YawRateValue(const cam_msgs::YawRateValue& in, YawRateValue_t& out) { - memset(&out, 0, sizeof(YawRateValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h index 6f7576fe2..a1d641c4b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AccelerationConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AccelerationConfidence(const AccelerationConfidence_t& in, denm_msgs::AccelerationConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccelerationConfidence(const denm_msgs::AccelerationConfidence& in, AccelerationConfidence_t& out) { - memset(&out, 0, sizeof(AccelerationConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h index ababe3fc3..8035158d4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING AccelerationControl -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AccelerationControl(const AccelerationControl_t& in, denm_msgs::AccelerationControl& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_AccelerationControl(const denm_msgs::AccelerationControl& in, AccelerationControl_t& out) { - memset(&out, 0, sizeof(AccelerationControl_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h index f36634572..eb5b7166f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AccidentSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AccidentSubCauseCode(const AccidentSubCauseCode_t& in, denm_msgs::AccidentSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccidentSubCauseCode(const denm_msgs::AccidentSubCauseCode& in, AccidentSubCauseCode_t& out) { - memset(&out, 0, sizeof(AccidentSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index 90bdda43f..354dc4662 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ActionID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ActionID(const ActionID_t& in, denm_msgs::ActionID& out) { - toRos_StationID(in.originatingStationID, out.originating_station_id); toRos_SequenceNumber(in.sequenceNumber, out.sequence_number); } void toStruct_ActionID(const denm_msgs::ActionID& in, ActionID_t& out) { - memset(&out, 0, sizeof(ActionID_t)); toStruct_StationID(in.originating_station_id, out.originatingStationID); toStruct_SequenceNumber(in.sequence_number, out.sequenceNumber); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index c3a7c461c..a12f95aff 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionAdhesionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionAdhesionSubCauseCode(const AdverseWeatherCondition_AdhesionSubCauseCode_t& in, denm_msgs::AdverseWeatherConditionAdhesionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionAdhesionSubCauseCode(const denm_msgs::AdverseWeatherConditionAdhesionSubCauseCode& in, AdverseWeatherCondition_AdhesionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_AdhesionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 79ace78c2..40504bd83 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& in, denm_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const denm_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& in, AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index 205d287b9..f098f06dc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionPrecipitationSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionPrecipitationSubCauseCode(const AdverseWeatherCondition_PrecipitationSubCauseCode_t& in, denm_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionPrecipitationSubCauseCode(const denm_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& in, AdverseWeatherCondition_PrecipitationSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_PrecipitationSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index 55b16ff8c..d721b092f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AdverseWeatherConditionVisibilitySubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionVisibilitySubCauseCode(const AdverseWeatherCondition_VisibilitySubCauseCode_t& in, denm_msgs::AdverseWeatherConditionVisibilitySubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionVisibilitySubCauseCode(const denm_msgs::AdverseWeatherConditionVisibilitySubCauseCode& in, AdverseWeatherCondition_VisibilitySubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_VisibilitySubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 50a8ddcac..c5d89d47d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE AlacarteContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -45,79 +24,59 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AlacarteContainer(const AlacarteContainer_t& in, denm_msgs::AlacarteContainer& out) { - if (in.lanePosition) { toRos_LanePosition(*in.lanePosition, out.lane_position); out.lane_position_is_present = true; } - if (in.impactReduction) { toRos_ImpactReductionContainer(*in.impactReduction, out.impact_reduction); out.impact_reduction_is_present = true; } - if (in.externalTemperature) { toRos_Temperature(*in.externalTemperature, out.external_temperature); out.external_temperature_is_present = true; } - if (in.roadWorks) { toRos_RoadWorksContainerExtended(*in.roadWorks, out.road_works); out.road_works_is_present = true; } - if (in.positioningSolution) { toRos_PositioningSolutionType(*in.positioningSolution, out.positioning_solution); out.positioning_solution_is_present = true; } - if (in.stationaryVehicle) { toRos_StationaryVehicleContainer(*in.stationaryVehicle, out.stationary_vehicle); out.stationary_vehicle_is_present = true; } - } void toStruct_AlacarteContainer(const denm_msgs::AlacarteContainer& in, AlacarteContainer_t& out) { - memset(&out, 0, sizeof(AlacarteContainer_t)); if (in.lane_position_is_present) { - LanePosition_t lane_position; - toStruct_LanePosition(in.lane_position, lane_position); - out.lanePosition = new LanePosition_t(lane_position); + out.lanePosition = (LanePosition_t*) calloc(1, sizeof(LanePosition_t)); + toStruct_LanePosition(in.lane_position, *out.lanePosition); } - if (in.impact_reduction_is_present) { - ImpactReductionContainer_t impact_reduction; - toStruct_ImpactReductionContainer(in.impact_reduction, impact_reduction); - out.impactReduction = new ImpactReductionContainer_t(impact_reduction); + out.impactReduction = (ImpactReductionContainer_t*) calloc(1, sizeof(ImpactReductionContainer_t)); + toStruct_ImpactReductionContainer(in.impact_reduction, *out.impactReduction); } - if (in.external_temperature_is_present) { - Temperature_t external_temperature; - toStruct_Temperature(in.external_temperature, external_temperature); - out.externalTemperature = new Temperature_t(external_temperature); + out.externalTemperature = (Temperature_t*) calloc(1, sizeof(Temperature_t)); + toStruct_Temperature(in.external_temperature, *out.externalTemperature); } - if (in.road_works_is_present) { - RoadWorksContainerExtended_t road_works; - toStruct_RoadWorksContainerExtended(in.road_works, road_works); - out.roadWorks = new RoadWorksContainerExtended_t(road_works); + out.roadWorks = (RoadWorksContainerExtended_t*) calloc(1, sizeof(RoadWorksContainerExtended_t)); + toStruct_RoadWorksContainerExtended(in.road_works, *out.roadWorks); } - if (in.positioning_solution_is_present) { - PositioningSolutionType_t positioning_solution; - toStruct_PositioningSolutionType(in.positioning_solution, positioning_solution); - out.positioningSolution = new PositioningSolutionType_t(positioning_solution); + out.positioningSolution = (PositioningSolutionType_t*) calloc(1, sizeof(PositioningSolutionType_t)); + toStruct_PositioningSolutionType(in.positioning_solution, *out.positioningSolution); } - if (in.stationary_vehicle_is_present) { - StationaryVehicleContainer_t stationary_vehicle; - toStruct_StationaryVehicleContainer(in.stationary_vehicle, stationary_vehicle); - out.stationaryVehicle = new StationaryVehicleContainer_t(stationary_vehicle); + out.stationaryVehicle = (StationaryVehicleContainer_t*) calloc(1, sizeof(StationaryVehicleContainer_t)); + toStruct_StationaryVehicleContainer(in.stationary_vehicle, *out.stationaryVehicle); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index f1d0c3b90..a9fc51a42 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Altitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Altitude(const Altitude_t& in, denm_msgs::Altitude& out) { - toRos_AltitudeValue(in.altitudeValue, out.altitude_value); toRos_AltitudeConfidence(in.altitudeConfidence, out.altitude_confidence); } void toStruct_Altitude(const denm_msgs::Altitude& in, Altitude_t& out) { - memset(&out, 0, sizeof(Altitude_t)); toStruct_AltitudeValue(in.altitude_value, out.altitudeValue); toStruct_AltitudeConfidence(in.altitude_confidence, out.altitudeConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h index 149a3ef87..8866ed53f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED AltitudeConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AltitudeConfidence(const AltitudeConfidence_t& in, denm_msgs::AltitudeConfidence& out) { - out.value = in; } void toStruct_AltitudeConfidence(const denm_msgs::AltitudeConfidence& in, AltitudeConfidence_t& out) { - memset(&out, 0, sizeof(AltitudeConfidence_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h index ae5527343..2d7fbb00c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER AltitudeValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AltitudeValue(const AltitudeValue_t& in, denm_msgs::AltitudeValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AltitudeValue(const denm_msgs::AltitudeValue& in, AltitudeValue_t& out) { - memset(&out, 0, sizeof(AltitudeValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index 00e2d758a..c5f14d0e8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CauseCode(const CauseCode_t& in, denm_msgs::CauseCode& out) { - toRos_CauseCodeType(in.causeCode, out.cause_code); toRos_SubCauseCodeType(in.subCauseCode, out.sub_cause_code); } void toStruct_CauseCode(const denm_msgs::CauseCode& in, CauseCode_t& out) { - memset(&out, 0, sizeof(CauseCode_t)); toStruct_CauseCodeType(in.cause_code, out.causeCode); toStruct_SubCauseCodeType(in.sub_cause_code, out.subCauseCode); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h index 2f6fda285..1d86fec34 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER CauseCodeType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CauseCodeType(const CauseCodeType_t& in, denm_msgs::CauseCodeType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CauseCodeType(const denm_msgs::CauseCodeType& in, CauseCodeType_t& out) { - memset(&out, 0, sizeof(CauseCodeType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 0e482b9af..1f2ae2fb6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE CenDsrcTollingZone -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,28 +21,23 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CenDsrcTollingZone(const CenDsrcTollingZone_t& in, denm_msgs::CenDsrcTollingZone& out) { - toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.cenDsrcTollingZoneID) { toRos_CenDsrcTollingZoneID(*in.cenDsrcTollingZoneID, out.cen_dsrc_tolling_zone_id); out.cen_dsrc_tolling_zone_id_is_present = true; } - } void toStruct_CenDsrcTollingZone(const denm_msgs::CenDsrcTollingZone& in, CenDsrcTollingZone_t& out) { - memset(&out, 0, sizeof(CenDsrcTollingZone_t)); toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.cen_dsrc_tolling_zone_id_is_present) { - CenDsrcTollingZoneID_t cen_dsrc_tolling_zone_id; - toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, cen_dsrc_tolling_zone_id); - out.cenDsrcTollingZoneID = new CenDsrcTollingZoneID_t(cen_dsrc_tolling_zone_id); + out.cenDsrcTollingZoneID = (CenDsrcTollingZoneID_t*) calloc(1, sizeof(CenDsrcTollingZoneID_t)); + toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, *out.cenDsrcTollingZoneID); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h index 7ff1f0447..04cc68677 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// TYPEALIAS CenDsrcTollingZoneID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #ifdef ROS1 @@ -36,17 +15,17 @@ namespace denm_msgs = etsi_its_denm_msgs; namespace denm_msgs = etsi_its_denm_msgs::msg; #endif + namespace etsi_its_denm_conversion { void toRos_CenDsrcTollingZoneID(const CenDsrcTollingZoneID_t& in, denm_msgs::CenDsrcTollingZoneID& out) { - toRos_ProtectedZoneID(in, out.value); } void toStruct_CenDsrcTollingZoneID(const denm_msgs::CenDsrcTollingZoneID& in, CenDsrcTollingZoneID_t& out) { - memset(&out, 0, sizeof(CenDsrcTollingZoneID_t)); + toStruct_ProtectedZoneID(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index 401a0d560..c287b1575 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ClosedLanes -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,46 +21,35 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ClosedLanes(const ClosedLanes_t& in, denm_msgs::ClosedLanes& out) { - if (in.innerhardShoulderStatus) { toRos_HardShoulderStatus(*in.innerhardShoulderStatus, out.innerhard_shoulder_status); out.innerhard_shoulder_status_is_present = true; } - if (in.outerhardShoulderStatus) { toRos_HardShoulderStatus(*in.outerhardShoulderStatus, out.outerhard_shoulder_status); out.outerhard_shoulder_status_is_present = true; } - if (in.drivingLaneStatus) { toRos_DrivingLaneStatus(*in.drivingLaneStatus, out.driving_lane_status); out.driving_lane_status_is_present = true; } - } void toStruct_ClosedLanes(const denm_msgs::ClosedLanes& in, ClosedLanes_t& out) { - memset(&out, 0, sizeof(ClosedLanes_t)); if (in.innerhard_shoulder_status_is_present) { - HardShoulderStatus_t innerhard_shoulder_status; - toStruct_HardShoulderStatus(in.innerhard_shoulder_status, innerhard_shoulder_status); - out.innerhardShoulderStatus = new HardShoulderStatus_t(innerhard_shoulder_status); + out.innerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); + toStruct_HardShoulderStatus(in.innerhard_shoulder_status, *out.innerhardShoulderStatus); } - if (in.outerhard_shoulder_status_is_present) { - HardShoulderStatus_t outerhard_shoulder_status; - toStruct_HardShoulderStatus(in.outerhard_shoulder_status, outerhard_shoulder_status); - out.outerhardShoulderStatus = new HardShoulderStatus_t(outerhard_shoulder_status); + out.outerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); + toStruct_HardShoulderStatus(in.outerhard_shoulder_status, *out.outerhardShoulderStatus); } - if (in.driving_lane_status_is_present) { - DrivingLaneStatus_t driving_lane_status; - toStruct_DrivingLaneStatus(in.driving_lane_status, driving_lane_status); - out.drivingLaneStatus = new DrivingLaneStatus_t(driving_lane_status); + out.drivingLaneStatus = (DrivingLaneStatus_t*) calloc(1, sizeof(DrivingLaneStatus_t)); + toStruct_DrivingLaneStatus(in.driving_lane_status, *out.drivingLaneStatus); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h index 7903cc748..db868261e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER CollisionRiskSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CollisionRiskSubCauseCode(const CollisionRiskSubCauseCode_t& in, denm_msgs::CollisionRiskSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CollisionRiskSubCauseCode(const denm_msgs::CollisionRiskSubCauseCode& in, CollisionRiskSubCauseCode_t& out) { - memset(&out, 0, sizeof(CollisionRiskSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index 15ca78d64..413cfd35a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Curvature -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Curvature(const Curvature_t& in, denm_msgs::Curvature& out) { - toRos_CurvatureValue(in.curvatureValue, out.curvature_value); toRos_CurvatureConfidence(in.curvatureConfidence, out.curvature_confidence); } void toStruct_Curvature(const denm_msgs::Curvature& in, Curvature_t& out) { - memset(&out, 0, sizeof(Curvature_t)); toStruct_CurvatureValue(in.curvature_value, out.curvatureValue); toStruct_CurvatureConfidence(in.curvature_confidence, out.curvatureConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h index 8a4d41270..fa48affe0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED CurvatureCalculationMode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CurvatureCalculationMode(const CurvatureCalculationMode_t& in, denm_msgs::CurvatureCalculationMode& out) { - out.value = in; } void toStruct_CurvatureCalculationMode(const denm_msgs::CurvatureCalculationMode& in, CurvatureCalculationMode_t& out) { - memset(&out, 0, sizeof(CurvatureCalculationMode_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h index b9e8f1b42..21cba7145 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED CurvatureConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CurvatureConfidence(const CurvatureConfidence_t& in, denm_msgs::CurvatureConfidence& out) { - out.value = in; } void toStruct_CurvatureConfidence(const denm_msgs::CurvatureConfidence& in, CurvatureConfidence_t& out) { - memset(&out, 0, sizeof(CurvatureConfidence_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h index 731b27d43..423d4465a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER CurvatureValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CurvatureValue(const CurvatureValue_t& in, denm_msgs::CurvatureValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CurvatureValue(const denm_msgs::CurvatureValue& in, CurvatureValue_t& out) { - memset(&out, 0, sizeof(CurvatureValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h index 5034c5af5..97b3f8d64 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DENM -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DENM(const DENM_t& in, denm_msgs::DENM& out) { - toRos_ItsPduHeader(in.header, out.header); toRos_DecentralizedEnvironmentalNotificationMessage(in.denm, out.denm); } void toStruct_DENM(const denm_msgs::DENM& in, DENM_t& out) { - memset(&out, 0, sizeof(DENM_t)); toStruct_ItsPduHeader(in.header, out.header); toStruct_DecentralizedEnvironmentalNotificationMessage(in.denm, out.denm); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h index 297856458..a3cb2e180 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DangerousEndOfQueueSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousEndOfQueueSubCauseCode(const DangerousEndOfQueueSubCauseCode_t& in, denm_msgs::DangerousEndOfQueueSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousEndOfQueueSubCauseCode(const denm_msgs::DangerousEndOfQueueSubCauseCode& in, DangerousEndOfQueueSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousEndOfQueueSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h index c589cb24e..74c112437 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED DangerousGoodsBasic -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousGoodsBasic(const DangerousGoodsBasic_t& in, denm_msgs::DangerousGoodsBasic& out) { - out.value = in; } void toStruct_DangerousGoodsBasic(const denm_msgs::DangerousGoodsBasic& in, DangerousGoodsBasic_t& out) { - memset(&out, 0, sizeof(DangerousGoodsBasic_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index 538f96fb9..ff4dafb68 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -1,39 +1,24 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DangerousGoodsExtended -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include +#include #include +#include #include +#include #include +#include #include +#include #include #include +#include #include #ifdef ROS1 #include @@ -47,7 +32,6 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, denm_msgs::DangerousGoodsExtended& out) { - toRos_DangerousGoodsBasic(in.dangerousGoodsType, out.dangerous_goods_type); etsi_its_primitives_conversion::toRos_INTEGER(in.unNumber, out.un_number); etsi_its_primitives_conversion::toRos_BOOLEAN(in.elevatedTemperature, out.elevated_temperature); @@ -57,21 +41,17 @@ void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, denm_msgs: etsi_its_primitives_conversion::toRos_IA5String(*in.emergencyActionCode, out.emergency_action_code); out.emergency_action_code_is_present = true; } - if (in.phoneNumber) { toRos_PhoneNumber(*in.phoneNumber, out.phone_number); out.phone_number_is_present = true; } - if (in.companyName) { etsi_its_primitives_conversion::toRos_UTF8String(*in.companyName, out.company_name); out.company_name_is_present = true; } - } void toStruct_DangerousGoodsExtended(const denm_msgs::DangerousGoodsExtended& in, DangerousGoodsExtended_t& out) { - memset(&out, 0, sizeof(DangerousGoodsExtended_t)); toStruct_DangerousGoodsBasic(in.dangerous_goods_type, out.dangerousGoodsType); @@ -80,23 +60,17 @@ void toStruct_DangerousGoodsExtended(const denm_msgs::DangerousGoodsExtended& in etsi_its_primitives_conversion::toStruct_BOOLEAN(in.tunnels_restricted, out.tunnelsRestricted); etsi_its_primitives_conversion::toStruct_BOOLEAN(in.limited_quantity, out.limitedQuantity); if (in.emergency_action_code_is_present) { - IA5String_t emergency_action_code; - etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, emergency_action_code); - out.emergencyActionCode = new IA5String_t(emergency_action_code); + out.emergencyActionCode = (IA5String_t*) calloc(1, sizeof(IA5String_t)); + etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, *out.emergencyActionCode); } - if (in.phone_number_is_present) { - PhoneNumber_t phone_number; - toStruct_PhoneNumber(in.phone_number, phone_number); - out.phoneNumber = new PhoneNumber_t(phone_number); + out.phoneNumber = (PhoneNumber_t*) calloc(1, sizeof(PhoneNumber_t)); + toStruct_PhoneNumber(in.phone_number, *out.phoneNumber); } - if (in.company_name_is_present) { - UTF8String_t company_name; - etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, company_name); - out.companyName = new UTF8String_t(company_name); + out.companyName = (UTF8String_t*) calloc(1, sizeof(UTF8String_t)); + etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, *out.companyName); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h index 86bc33b99..e02ace1b0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DangerousSituationSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousSituationSubCauseCode(const DangerousSituationSubCauseCode_t& in, denm_msgs::DangerousSituationSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousSituationSubCauseCode(const denm_msgs::DangerousSituationSubCauseCode& in, DangerousSituationSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousSituationSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index 9c7d1a667..174e1def8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DecentralizedEnvironmentalNotificationMessage -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,48 +22,37 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DecentralizedEnvironmentalNotificationMessage(const DecentralizedEnvironmentalNotificationMessage_t& in, denm_msgs::DecentralizedEnvironmentalNotificationMessage& out) { - toRos_ManagementContainer(in.management, out.management); if (in.situation) { toRos_SituationContainer(*in.situation, out.situation); out.situation_is_present = true; } - if (in.location) { toRos_LocationContainer(*in.location, out.location); out.location_is_present = true; } - if (in.alacarte) { toRos_AlacarteContainer(*in.alacarte, out.alacarte); out.alacarte_is_present = true; } - } void toStruct_DecentralizedEnvironmentalNotificationMessage(const denm_msgs::DecentralizedEnvironmentalNotificationMessage& in, DecentralizedEnvironmentalNotificationMessage_t& out) { - memset(&out, 0, sizeof(DecentralizedEnvironmentalNotificationMessage_t)); toStruct_ManagementContainer(in.management, out.management); if (in.situation_is_present) { - SituationContainer_t situation; - toStruct_SituationContainer(in.situation, situation); - out.situation = new SituationContainer_t(situation); + out.situation = (SituationContainer_t*) calloc(1, sizeof(SituationContainer_t)); + toStruct_SituationContainer(in.situation, *out.situation); } - if (in.location_is_present) { - LocationContainer_t location; - toStruct_LocationContainer(in.location, location); - out.location = new LocationContainer_t(location); + out.location = (LocationContainer_t*) calloc(1, sizeof(LocationContainer_t)); + toStruct_LocationContainer(in.location, *out.location); } - if (in.alacarte_is_present) { - AlacarteContainer_t alacarte; - toStruct_AlacarteContainer(in.alacarte, alacarte); - out.alacarte = new AlacarteContainer_t(alacarte); + out.alacarte = (AlacarteContainer_t*) calloc(1, sizeof(AlacarteContainer_t)); + toStruct_AlacarteContainer(in.alacarte, *out.alacarte); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h index 260939d4e..4289a1ad1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DeltaAltitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaAltitude(const DeltaAltitude_t& in, denm_msgs::DeltaAltitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaAltitude(const denm_msgs::DeltaAltitude& in, DeltaAltitude_t& out) { - memset(&out, 0, sizeof(DeltaAltitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h index c4c01b149..b2be76d9f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DeltaLatitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaLatitude(const DeltaLatitude_t& in, denm_msgs::DeltaLatitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLatitude(const denm_msgs::DeltaLatitude& in, DeltaLatitude_t& out) { - memset(&out, 0, sizeof(DeltaLatitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h index 599747fdf..b32f71083 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER DeltaLongitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaLongitude(const DeltaLongitude_t& in, denm_msgs::DeltaLongitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLongitude(const denm_msgs::DeltaLongitude& in, DeltaLongitude_t& out) { - memset(&out, 0, sizeof(DeltaLongitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index 46ffcfe24..5a459ba6e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE DeltaReferencePosition -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,14 +21,12 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaReferencePosition(const DeltaReferencePosition_t& in, denm_msgs::DeltaReferencePosition& out) { - toRos_DeltaLatitude(in.deltaLatitude, out.delta_latitude); toRos_DeltaLongitude(in.deltaLongitude, out.delta_longitude); toRos_DeltaAltitude(in.deltaAltitude, out.delta_altitude); } void toStruct_DeltaReferencePosition(const denm_msgs::DeltaReferencePosition& in, DeltaReferencePosition_t& out) { - memset(&out, 0, sizeof(DeltaReferencePosition_t)); toStruct_DeltaLatitude(in.delta_latitude, out.deltaLatitude); @@ -57,4 +34,4 @@ void toStruct_DeltaReferencePosition(const denm_msgs::DeltaReferencePosition& in toStruct_DeltaAltitude(in.delta_altitude, out.deltaAltitude); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h index ac3bc24e0..be3c0b1eb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF DigitalMap -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DigitalMap(const DigitalMap_t& in, denm_msgs::DigitalMap& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::ReferencePosition array; - toRos_ReferencePosition(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::ReferencePosition el; + toRos_ReferencePosition(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_DigitalMap(const denm_msgs::DigitalMap& in, DigitalMap_t& out) { - memset(&out, 0, sizeof(DigitalMap_t)); - for (int i = 0; i < in.array.size(); i++) { - ReferencePosition_t array; - toStruct_ReferencePosition(in.array[i], array); - ReferencePosition_t* array_ptr = new ReferencePosition_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); + toStruct_ReferencePosition(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h index fcedc7180..d96877308 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED DriveDirection -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DriveDirection(const DriveDirection_t& in, denm_msgs::DriveDirection& out) { - out.value = in; } void toStruct_DriveDirection(const denm_msgs::DriveDirection& in, DriveDirection_t& out) { - memset(&out, 0, sizeof(DriveDirection_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h index 6770f0af0..31847df68 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING DrivingLaneStatus -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DrivingLaneStatus(const DrivingLaneStatus_t& in, denm_msgs::DrivingLaneStatus& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_DrivingLaneStatus(const denm_msgs::DrivingLaneStatus& in, DrivingLaneStatus_t& out) { - memset(&out, 0, sizeof(DrivingLaneStatus_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h index dbc333cd4..ce8bcd728 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BOOLEAN EmbarkationStatus -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EmbarkationStatus(const EmbarkationStatus_t& in, denm_msgs::EmbarkationStatus& out) { - etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value); } void toStruct_EmbarkationStatus(const denm_msgs::EmbarkationStatus& in, EmbarkationStatus_t& out) { - memset(&out, 0, sizeof(EmbarkationStatus_t)); + etsi_its_primitives_conversion::toStruct_BOOLEAN(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h index 8839534af..3e1740f23 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING EmergencyPriority -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EmergencyPriority(const EmergencyPriority_t& in, denm_msgs::EmergencyPriority& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EmergencyPriority(const denm_msgs::EmergencyPriority& in, EmergencyPriority_t& out) { - memset(&out, 0, sizeof(EmergencyPriority_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 4e500cd84..40b21ac10 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER EmergencyVehicleApproachingSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EmergencyVehicleApproachingSubCauseCode(const EmergencyVehicleApproachingSubCauseCode_t& in, denm_msgs::EmergencyVehicleApproachingSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_EmergencyVehicleApproachingSubCauseCode(const denm_msgs::EmergencyVehicleApproachingSubCauseCode& in, EmergencyVehicleApproachingSubCauseCode_t& out) { - memset(&out, 0, sizeof(EmergencyVehicleApproachingSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h index c292d395a..78bb25f92 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING EnergyStorageType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EnergyStorageType(const EnergyStorageType_t& in, denm_msgs::EnergyStorageType& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EnergyStorageType(const denm_msgs::EnergyStorageType& in, EnergyStorageType_t& out) { - memset(&out, 0, sizeof(EnergyStorageType_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h index 2ffbc6a15..d07c8a47c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF EventHistory -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EventHistory(const EventHistory_t& in, denm_msgs::EventHistory& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::EventPoint array; - toRos_EventPoint(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::EventPoint el; + toRos_EventPoint(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_EventHistory(const denm_msgs::EventHistory& in, EventHistory_t& out) { - memset(&out, 0, sizeof(EventHistory_t)); - for (int i = 0; i < in.array.size(); i++) { - EventPoint_t array; - toStruct_EventPoint(in.array[i], array); - EventPoint_t* array_ptr = new EventPoint_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + EventPoint_t* el = (EventPoint_t*) calloc(1, sizeof(EventPoint_t)); + toStruct_EventPoint(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index 1904017d1..b15402196 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE EventPoint -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,28 +21,23 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EventPoint(const EventPoint_t& in, denm_msgs::EventPoint& out) { - toRos_DeltaReferencePosition(in.eventPosition, out.event_position); if (in.eventDeltaTime) { toRos_PathDeltaTime(*in.eventDeltaTime, out.event_delta_time); out.event_delta_time_is_present = true; } - toRos_InformationQuality(in.informationQuality, out.information_quality); } void toStruct_EventPoint(const denm_msgs::EventPoint& in, EventPoint_t& out) { - memset(&out, 0, sizeof(EventPoint_t)); toStruct_DeltaReferencePosition(in.event_position, out.eventPosition); if (in.event_delta_time_is_present) { - PathDeltaTime_t event_delta_time; - toStruct_PathDeltaTime(in.event_delta_time, event_delta_time); - out.eventDeltaTime = new PathDeltaTime_t(event_delta_time); + out.eventDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); + toStruct_PathDeltaTime(in.event_delta_time, *out.eventDeltaTime); } - toStruct_InformationQuality(in.information_quality, out.informationQuality); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h index 58a098d73..fd073fdec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING ExteriorLights -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ExteriorLights(const ExteriorLights_t& in, denm_msgs::ExteriorLights& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_ExteriorLights(const denm_msgs::ExteriorLights& in, ExteriorLights_t& out) { - memset(&out, 0, sizeof(ExteriorLights_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h index 1fcdeb4ad..49e07d73d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED HardShoulderStatus -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HardShoulderStatus(const HardShoulderStatus_t& in, denm_msgs::HardShoulderStatus& out) { - out.value = in; } void toStruct_HardShoulderStatus(const denm_msgs::HardShoulderStatus& in, HardShoulderStatus_t& out) { - memset(&out, 0, sizeof(HardShoulderStatus_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 964b4afce..aacddcd87 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationAnimalOnTheRoadSubCauseCode(const HazardousLocation_AnimalOnTheRoadSubCauseCode_t& in, denm_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationAnimalOnTheRoadSubCauseCode(const denm_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& in, HazardousLocation_AnimalOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_AnimalOnTheRoadSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index 47a672896..1e5e15b50 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationDangerousCurveSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationDangerousCurveSubCauseCode(const HazardousLocation_DangerousCurveSubCauseCode_t& in, denm_msgs::HazardousLocationDangerousCurveSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationDangerousCurveSubCauseCode(const denm_msgs::HazardousLocationDangerousCurveSubCauseCode& in, HazardousLocation_DangerousCurveSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_DangerousCurveSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index 38fd6dccc..ff6cbe3a5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationObstacleOnTheRoadSubCauseCode(const HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& in, denm_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationObstacleOnTheRoadSubCauseCode(const denm_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& in, HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_ObstacleOnTheRoadSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index d91d2697b..83c9c8fc7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HazardousLocationSurfaceConditionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationSurfaceConditionSubCauseCode(const HazardousLocation_SurfaceConditionSubCauseCode_t& in, denm_msgs::HazardousLocationSurfaceConditionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationSurfaceConditionSubCauseCode(const denm_msgs::HazardousLocationSurfaceConditionSubCauseCode& in, HazardousLocation_SurfaceConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_SurfaceConditionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index 6005aa926..9b6422494 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Heading -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Heading(const Heading_t& in, denm_msgs::Heading& out) { - toRos_HeadingValue(in.headingValue, out.heading_value); toRos_HeadingConfidence(in.headingConfidence, out.heading_confidence); } void toStruct_Heading(const denm_msgs::Heading& in, Heading_t& out) { - memset(&out, 0, sizeof(Heading_t)); toStruct_HeadingValue(in.heading_value, out.headingValue); toStruct_HeadingConfidence(in.heading_confidence, out.headingConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h index 22acd9eca..19374a60d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HeadingConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HeadingConfidence(const HeadingConfidence_t& in, denm_msgs::HeadingConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingConfidence(const denm_msgs::HeadingConfidence& in, HeadingConfidence_t& out) { - memset(&out, 0, sizeof(HeadingConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h index 4e4cc190e..2590e1196 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HeadingValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HeadingValue(const HeadingValue_t& in, denm_msgs::HeadingValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingValue(const denm_msgs::HeadingValue& in, HeadingValue_t& out) { - memset(&out, 0, sizeof(HeadingValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h index ab6f250d9..b75b1e29c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HeightLonCarr -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HeightLonCarr(const HeightLonCarr_t& in, denm_msgs::HeightLonCarr& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeightLonCarr(const denm_msgs::HeightLonCarr& in, HeightLonCarr_t& out) { - memset(&out, 0, sizeof(HeightLonCarr_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index fb249336c..6b0fa421b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HumanPresenceOnTheRoadSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HumanPresenceOnTheRoadSubCauseCode(const HumanPresenceOnTheRoadSubCauseCode_t& in, denm_msgs::HumanPresenceOnTheRoadSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanPresenceOnTheRoadSubCauseCode(const denm_msgs::HumanPresenceOnTheRoadSubCauseCode& in, HumanPresenceOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanPresenceOnTheRoadSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h index dee227fa5..22f3764da 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER HumanProblemSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HumanProblemSubCauseCode(const HumanProblemSubCauseCode_t& in, denm_msgs::HumanProblemSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanProblemSubCauseCode(const denm_msgs::HumanProblemSubCauseCode& in, HumanProblemSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanProblemSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index a99073bb9..8e5b2eb5c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ImpactReductionContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -51,7 +30,6 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ImpactReductionContainer(const ImpactReductionContainer_t& in, denm_msgs::ImpactReductionContainer& out) { - toRos_HeightLonCarr(in.heightLonCarrLeft, out.height_lon_carr_left); toRos_HeightLonCarr(in.heightLonCarrRight, out.height_lon_carr_right); toRos_PosLonCarr(in.posLonCarrLeft, out.pos_lon_carr_left); @@ -67,7 +45,6 @@ void toRos_ImpactReductionContainer(const ImpactReductionContainer_t& in, denm_m } void toStruct_ImpactReductionContainer(const denm_msgs::ImpactReductionContainer& in, ImpactReductionContainer_t& out) { - memset(&out, 0, sizeof(ImpactReductionContainer_t)); toStruct_HeightLonCarr(in.height_lon_carr_left, out.heightLonCarrLeft); @@ -84,4 +61,4 @@ void toStruct_ImpactReductionContainer(const denm_msgs::ImpactReductionContainer toStruct_RequestResponseIndication(in.request_response_indication, out.requestResponseIndication); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h index 76fb0dc8c..444a6bbe4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER InformationQuality -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_InformationQuality(const InformationQuality_t& in, denm_msgs::InformationQuality& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_InformationQuality(const denm_msgs::InformationQuality& in, InformationQuality_t& out) { - memset(&out, 0, sizeof(InformationQuality_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index ed2ea6522..957758cce 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF ItineraryPath -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ItineraryPath(const ItineraryPath_t& in, denm_msgs::ItineraryPath& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::ReferencePosition array; - toRos_ReferencePosition(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::ReferencePosition el; + toRos_ReferencePosition(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_ItineraryPath(const denm_msgs::ItineraryPath& in, ItineraryPath_t& out) { - memset(&out, 0, sizeof(ItineraryPath_t)); - for (int i = 0; i < in.array.size(); i++) { - ReferencePosition_t array; - toStruct_ReferencePosition(in.array[i], array); - ReferencePosition_t* array_ptr = new ReferencePosition_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); + toStruct_ReferencePosition(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index fc8e24709..21e550b9d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -1,33 +1,14 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ItsPduHeader -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include +#include #include +#include #include #include #ifdef ROS1 @@ -42,14 +23,12 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ItsPduHeader(const ItsPduHeader_t& in, denm_msgs::ItsPduHeader& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in.protocolVersion, out.protocol_version); etsi_its_primitives_conversion::toRos_INTEGER(in.messageID, out.message_id); toRos_StationID(in.stationID, out.station_id); } void toStruct_ItsPduHeader(const denm_msgs::ItsPduHeader& in, ItsPduHeader_t& out) { - memset(&out, 0, sizeof(ItsPduHeader_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.protocol_version, out.protocolVersion); @@ -57,4 +36,4 @@ void toStruct_ItsPduHeader(const denm_msgs::ItsPduHeader& in, ItsPduHeader_t& ou toStruct_StationID(in.station_id, out.stationID); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h index 4f6dd7b30..b13c33742 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER LanePosition -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LanePosition(const LanePosition_t& in, denm_msgs::LanePosition& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LanePosition(const denm_msgs::LanePosition& in, LanePosition_t& out) { - memset(&out, 0, sizeof(LanePosition_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h index bf49dc0c0..6a2235fbc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE LateralAcceleration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LateralAcceleration(const LateralAcceleration_t& in, denm_msgs::LateralAcceleration& out) { - toRos_LateralAccelerationValue(in.lateralAccelerationValue, out.lateral_acceleration_value); toRos_AccelerationConfidence(in.lateralAccelerationConfidence, out.lateral_acceleration_confidence); } void toStruct_LateralAcceleration(const denm_msgs::LateralAcceleration& in, LateralAcceleration_t& out) { - memset(&out, 0, sizeof(LateralAcceleration_t)); toStruct_LateralAccelerationValue(in.lateral_acceleration_value, out.lateralAccelerationValue); toStruct_AccelerationConfidence(in.lateral_acceleration_confidence, out.lateralAccelerationConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h index 8c13da0e1..186bc1e24 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER LateralAccelerationValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LateralAccelerationValue(const LateralAccelerationValue_t& in, denm_msgs::LateralAccelerationValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LateralAccelerationValue(const denm_msgs::LateralAccelerationValue& in, LateralAccelerationValue_t& out) { - memset(&out, 0, sizeof(LateralAccelerationValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h index 62e7d34e9..607841873 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER Latitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Latitude(const Latitude_t& in, denm_msgs::Latitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Latitude(const denm_msgs::Latitude& in, Latitude_t& out) { - memset(&out, 0, sizeof(Latitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h index fe29a5da9..4a4fe5a49 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING LightBarSirenInUse -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LightBarSirenInUse(const LightBarSirenInUse_t& in, denm_msgs::LightBarSirenInUse& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_LightBarSirenInUse(const denm_msgs::LightBarSirenInUse& in, LightBarSirenInUse_t& out) { - memset(&out, 0, sizeof(LightBarSirenInUse_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index e9fce0141..82ca0a858 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE LocationContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,48 +22,37 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LocationContainer(const LocationContainer_t& in, denm_msgs::LocationContainer& out) { - if (in.eventSpeed) { toRos_Speed(*in.eventSpeed, out.event_speed); out.event_speed_is_present = true; } - if (in.eventPositionHeading) { toRos_Heading(*in.eventPositionHeading, out.event_position_heading); out.event_position_heading_is_present = true; } - toRos_Traces(in.traces, out.traces); if (in.roadType) { toRos_RoadType(*in.roadType, out.road_type); out.road_type_is_present = true; } - } void toStruct_LocationContainer(const denm_msgs::LocationContainer& in, LocationContainer_t& out) { - memset(&out, 0, sizeof(LocationContainer_t)); if (in.event_speed_is_present) { - Speed_t event_speed; - toStruct_Speed(in.event_speed, event_speed); - out.eventSpeed = new Speed_t(event_speed); + out.eventSpeed = (Speed_t*) calloc(1, sizeof(Speed_t)); + toStruct_Speed(in.event_speed, *out.eventSpeed); } - if (in.event_position_heading_is_present) { - Heading_t event_position_heading; - toStruct_Heading(in.event_position_heading, event_position_heading); - out.eventPositionHeading = new Heading_t(event_position_heading); + out.eventPositionHeading = (Heading_t*) calloc(1, sizeof(Heading_t)); + toStruct_Heading(in.event_position_heading, *out.eventPositionHeading); } - toStruct_Traces(in.traces, out.traces); if (in.road_type_is_present) { - RoadType_t road_type; - toStruct_RoadType(in.road_type, road_type); - out.roadType = new RoadType_t(road_type); + out.roadType = (RoadType_t*) calloc(1, sizeof(RoadType_t)); + toStruct_RoadType(in.road_type, *out.roadType); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h index e87557abc..2c5a00086 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER Longitude -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Longitude(const Longitude_t& in, denm_msgs::Longitude& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Longitude(const denm_msgs::Longitude& in, Longitude_t& out) { - memset(&out, 0, sizeof(Longitude_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index 9a7a64174..a6866e221 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE LongitudinalAcceleration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LongitudinalAcceleration(const LongitudinalAcceleration_t& in, denm_msgs::LongitudinalAcceleration& out) { - toRos_LongitudinalAccelerationValue(in.longitudinalAccelerationValue, out.longitudinal_acceleration_value); toRos_AccelerationConfidence(in.longitudinalAccelerationConfidence, out.longitudinal_acceleration_confidence); } void toStruct_LongitudinalAcceleration(const denm_msgs::LongitudinalAcceleration& in, LongitudinalAcceleration_t& out) { - memset(&out, 0, sizeof(LongitudinalAcceleration_t)); toStruct_LongitudinalAccelerationValue(in.longitudinal_acceleration_value, out.longitudinalAccelerationValue); toStruct_AccelerationConfidence(in.longitudinal_acceleration_confidence, out.longitudinalAccelerationConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h index ad1a820be..9162a1393 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER LongitudinalAccelerationValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LongitudinalAccelerationValue(const LongitudinalAccelerationValue_t& in, denm_msgs::LongitudinalAccelerationValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LongitudinalAccelerationValue(const denm_msgs::LongitudinalAccelerationValue& in, LongitudinalAccelerationValue_t& out) { - memset(&out, 0, sizeof(LongitudinalAccelerationValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index 6b6687623..66230914c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ManagementContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -49,7 +28,6 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ManagementContainer(const ManagementContainer_t& in, denm_msgs::ManagementContainer& out) { - toRos_ActionID(in.actionID, out.action_id); toRos_TimestampIts(in.detectionTime, out.detection_time); toRos_TimestampIts(in.referenceTime, out.reference_time); @@ -57,67 +35,51 @@ void toRos_ManagementContainer(const ManagementContainer_t& in, denm_msgs::Manag toRos_Termination(*in.termination, out.termination); out.termination_is_present = true; } - toRos_ReferencePosition(in.eventPosition, out.event_position); if (in.relevanceDistance) { toRos_RelevanceDistance(*in.relevanceDistance, out.relevance_distance); out.relevance_distance_is_present = true; } - if (in.relevanceTrafficDirection) { toRos_RelevanceTrafficDirection(*in.relevanceTrafficDirection, out.relevance_traffic_direction); out.relevance_traffic_direction_is_present = true; } - if (in.validityDuration) { toRos_ValidityDuration(*in.validityDuration, out.validity_duration); } - if (in.transmissionInterval) { toRos_TransmissionInterval(*in.transmissionInterval, out.transmission_interval); out.transmission_interval_is_present = true; } - toRos_StationType(in.stationType, out.station_type); } void toStruct_ManagementContainer(const denm_msgs::ManagementContainer& in, ManagementContainer_t& out) { - memset(&out, 0, sizeof(ManagementContainer_t)); toStruct_ActionID(in.action_id, out.actionID); toStruct_TimestampIts(in.detection_time, out.detectionTime); toStruct_TimestampIts(in.reference_time, out.referenceTime); if (in.termination_is_present) { - Termination_t termination; - toStruct_Termination(in.termination, termination); - out.termination = new Termination_t(termination); + out.termination = (Termination_t*) calloc(1, sizeof(Termination_t)); + toStruct_Termination(in.termination, *out.termination); } - toStruct_ReferencePosition(in.event_position, out.eventPosition); if (in.relevance_distance_is_present) { - RelevanceDistance_t relevance_distance; - toStruct_RelevanceDistance(in.relevance_distance, relevance_distance); - out.relevanceDistance = new RelevanceDistance_t(relevance_distance); + out.relevanceDistance = (RelevanceDistance_t*) calloc(1, sizeof(RelevanceDistance_t)); + toStruct_RelevanceDistance(in.relevance_distance, *out.relevanceDistance); } - if (in.relevance_traffic_direction_is_present) { - RelevanceTrafficDirection_t relevance_traffic_direction; - toStruct_RelevanceTrafficDirection(in.relevance_traffic_direction, relevance_traffic_direction); - out.relevanceTrafficDirection = new RelevanceTrafficDirection_t(relevance_traffic_direction); + out.relevanceTrafficDirection = (RelevanceTrafficDirection_t*) calloc(1, sizeof(RelevanceTrafficDirection_t)); + toStruct_RelevanceTrafficDirection(in.relevance_traffic_direction, *out.relevanceTrafficDirection); } - - ValidityDuration_t validity_duration; - toStruct_ValidityDuration(in.validity_duration, validity_duration); - out.validityDuration = new ValidityDuration_t(validity_duration); - + out.validityDuration = (ValidityDuration_t*) calloc(1, sizeof(ValidityDuration_t)); + toStruct_ValidityDuration(in.validity_duration, *out.validityDuration); if (in.transmission_interval_is_present) { - TransmissionInterval_t transmission_interval; - toStruct_TransmissionInterval(in.transmission_interval, transmission_interval); - out.transmissionInterval = new TransmissionInterval_t(transmission_interval); + out.transmissionInterval = (TransmissionInterval_t*) calloc(1, sizeof(TransmissionInterval_t)); + toStruct_TransmissionInterval(in.transmission_interval, *out.transmissionInterval); } - toStruct_StationType(in.station_type, out.stationType); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h index b693932c2..cf653ff3c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER NumberOfOccupants -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_NumberOfOccupants(const NumberOfOccupants_t& in, denm_msgs::NumberOfOccupants& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_NumberOfOccupants(const denm_msgs::NumberOfOccupants& in, NumberOfOccupants_t& out) { - memset(&out, 0, sizeof(NumberOfOccupants_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h index 1aab4e75d..6277e9f14 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// UTF8String OpeningDaysHours -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_OpeningDaysHours(const OpeningDaysHours_t& in, denm_msgs::OpeningDaysHours& out) { - etsi_its_primitives_conversion::toRos_UTF8String(in, out.value); } void toStruct_OpeningDaysHours(const denm_msgs::OpeningDaysHours& in, OpeningDaysHours_t& out) { - memset(&out, 0, sizeof(OpeningDaysHours_t)); + etsi_its_primitives_conversion::toStruct_UTF8String(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h index e3f921a51..4dced4b2b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PathDeltaTime -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PathDeltaTime(const PathDeltaTime_t& in, denm_msgs::PathDeltaTime& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PathDeltaTime(const denm_msgs::PathDeltaTime& in, PathDeltaTime_t& out) { - memset(&out, 0, sizeof(PathDeltaTime_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h index 059c06ba7..88652a850 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF PathHistory -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PathHistory(const PathHistory_t& in, denm_msgs::PathHistory& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::PathPoint array; - toRos_PathPoint(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::PathPoint el; + toRos_PathPoint(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_PathHistory(const denm_msgs::PathHistory& in, PathHistory_t& out) { - memset(&out, 0, sizeof(PathHistory_t)); - for (int i = 0; i < in.array.size(); i++) { - PathPoint_t array; - toStruct_PathPoint(in.array[i], array); - PathPoint_t* array_ptr = new PathPoint_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + PathPoint_t* el = (PathPoint_t*) calloc(1, sizeof(PathPoint_t)); + toStruct_PathPoint(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index d6f6f2b8d..be4921fa9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PathPoint -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,26 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PathPoint(const PathPoint_t& in, denm_msgs::PathPoint& out) { - toRos_DeltaReferencePosition(in.pathPosition, out.path_position); if (in.pathDeltaTime) { toRos_PathDeltaTime(*in.pathDeltaTime, out.path_delta_time); out.path_delta_time_is_present = true; } - } void toStruct_PathPoint(const denm_msgs::PathPoint& in, PathPoint_t& out) { - memset(&out, 0, sizeof(PathPoint_t)); toStruct_DeltaReferencePosition(in.path_position, out.pathPosition); if (in.path_delta_time_is_present) { - PathDeltaTime_t path_delta_time; - toStruct_PathDeltaTime(in.path_delta_time, path_delta_time); - out.pathDeltaTime = new PathDeltaTime_t(path_delta_time); + out.pathDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); + toStruct_PathDeltaTime(in.path_delta_time, *out.pathDeltaTime); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h index 51b3e6dd4..9dfc6a278 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PerformanceClass -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PerformanceClass(const PerformanceClass_t& in, denm_msgs::PerformanceClass& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PerformanceClass(const denm_msgs::PerformanceClass& in, PerformanceClass_t& out) { - memset(&out, 0, sizeof(PerformanceClass_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h index a77882ea0..767730c15 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// NumericString PhoneNumber -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PhoneNumber(const PhoneNumber_t& in, denm_msgs::PhoneNumber& out) { - etsi_its_primitives_conversion::toRos_NumericString(in, out.value); } void toStruct_PhoneNumber(const denm_msgs::PhoneNumber& in, PhoneNumber_t& out) { - memset(&out, 0, sizeof(PhoneNumber_t)); + etsi_its_primitives_conversion::toStruct_NumericString(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h index 54ce41e9d..90c766f11 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosCentMass -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosCentMass(const PosCentMass_t& in, denm_msgs::PosCentMass& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosCentMass(const denm_msgs::PosCentMass& in, PosCentMass_t& out) { - memset(&out, 0, sizeof(PosCentMass_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 0ed2e6736..3cb06f59c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PosConfidenceEllipse -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -42,14 +21,12 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosConfidenceEllipse(const PosConfidenceEllipse_t& in, denm_msgs::PosConfidenceEllipse& out) { - toRos_SemiAxisLength(in.semiMajorConfidence, out.semi_major_confidence); toRos_SemiAxisLength(in.semiMinorConfidence, out.semi_minor_confidence); toRos_HeadingValue(in.semiMajorOrientation, out.semi_major_orientation); } void toStruct_PosConfidenceEllipse(const denm_msgs::PosConfidenceEllipse& in, PosConfidenceEllipse_t& out) { - memset(&out, 0, sizeof(PosConfidenceEllipse_t)); toStruct_SemiAxisLength(in.semi_major_confidence, out.semiMajorConfidence); @@ -57,4 +34,4 @@ void toStruct_PosConfidenceEllipse(const denm_msgs::PosConfidenceEllipse& in, Po toStruct_HeadingValue(in.semi_major_orientation, out.semiMajorOrientation); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h index cceb58a82..2d75b7325 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosFrontAx -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosFrontAx(const PosFrontAx_t& in, denm_msgs::PosFrontAx& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosFrontAx(const denm_msgs::PosFrontAx& in, PosFrontAx_t& out) { - memset(&out, 0, sizeof(PosFrontAx_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h index f7c17bbcd..618ab3703 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosLonCarr -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosLonCarr(const PosLonCarr_t& in, denm_msgs::PosLonCarr& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosLonCarr(const denm_msgs::PosLonCarr& in, PosLonCarr_t& out) { - memset(&out, 0, sizeof(PosLonCarr_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h index db3a63bed..e651cf425 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PosPillar -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosPillar(const PosPillar_t& in, denm_msgs::PosPillar& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosPillar(const denm_msgs::PosPillar& in, PosPillar_t& out) { - memset(&out, 0, sizeof(PosPillar_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h index 27f26626a..d752fa263 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING PositionOfOccupants -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PositionOfOccupants(const PositionOfOccupants_t& in, denm_msgs::PositionOfOccupants& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_PositionOfOccupants(const denm_msgs::PositionOfOccupants& in, PositionOfOccupants_t& out) { - memset(&out, 0, sizeof(PositionOfOccupants_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h index f91112aa1..7ba6314ab 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF PositionOfPillars -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PositionOfPillars(const PositionOfPillars_t& in, denm_msgs::PositionOfPillars& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::PosPillar array; - toRos_PosPillar(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::PosPillar el; + toRos_PosPillar(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_PositionOfPillars(const denm_msgs::PositionOfPillars& in, PositionOfPillars_t& out) { - memset(&out, 0, sizeof(PositionOfPillars_t)); - for (int i = 0; i < in.array.size(); i++) { - PosPillar_t array; - toStruct_PosPillar(in.array[i], array); - PosPillar_t* array_ptr = new PosPillar_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + PosPillar_t* el = (PosPillar_t*) calloc(1, sizeof(PosPillar_t)); + toStruct_PosPillar(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h index a6a4428e2..5d2b84f0d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED PositioningSolutionType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PositioningSolutionType(const PositioningSolutionType_t& in, denm_msgs::PositioningSolutionType& out) { - out.value = in; } void toStruct_PositioningSolutionType(const denm_msgs::PositioningSolutionType& in, PositioningSolutionType_t& out) { - memset(&out, 0, sizeof(PositioningSolutionType_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h index ace609eeb..063d0f40a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PostCrashSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PostCrashSubCauseCode(const PostCrashSubCauseCode_t& in, denm_msgs::PostCrashSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PostCrashSubCauseCode(const denm_msgs::PostCrashSubCauseCode& in, PostCrashSubCauseCode_t& out) { - memset(&out, 0, sizeof(PostCrashSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index 04859a769..ef459c648 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ProtectedCommunicationZone -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -45,52 +24,41 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedCommunicationZone(const ProtectedCommunicationZone_t& in, denm_msgs::ProtectedCommunicationZone& out) { - toRos_ProtectedZoneType(in.protectedZoneType, out.protected_zone_type); if (in.expiryTime) { toRos_TimestampIts(*in.expiryTime, out.expiry_time); out.expiry_time_is_present = true; } - toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.protectedZoneRadius) { toRos_ProtectedZoneRadius(*in.protectedZoneRadius, out.protected_zone_radius); out.protected_zone_radius_is_present = true; } - if (in.protectedZoneID) { toRos_ProtectedZoneID(*in.protectedZoneID, out.protected_zone_id); out.protected_zone_id_is_present = true; } - } void toStruct_ProtectedCommunicationZone(const denm_msgs::ProtectedCommunicationZone& in, ProtectedCommunicationZone_t& out) { - memset(&out, 0, sizeof(ProtectedCommunicationZone_t)); toStruct_ProtectedZoneType(in.protected_zone_type, out.protectedZoneType); if (in.expiry_time_is_present) { - TimestampIts_t expiry_time; - toStruct_TimestampIts(in.expiry_time, expiry_time); - out.expiryTime = new TimestampIts_t(expiry_time); + out.expiryTime = (TimestampIts_t*) calloc(1, sizeof(TimestampIts_t)); + toStruct_TimestampIts(in.expiry_time, *out.expiryTime); } - toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.protected_zone_radius_is_present) { - ProtectedZoneRadius_t protected_zone_radius; - toStruct_ProtectedZoneRadius(in.protected_zone_radius, protected_zone_radius); - out.protectedZoneRadius = new ProtectedZoneRadius_t(protected_zone_radius); + out.protectedZoneRadius = (ProtectedZoneRadius_t*) calloc(1, sizeof(ProtectedZoneRadius_t)); + toStruct_ProtectedZoneRadius(in.protected_zone_radius, *out.protectedZoneRadius); } - if (in.protected_zone_id_is_present) { - ProtectedZoneID_t protected_zone_id; - toStruct_ProtectedZoneID(in.protected_zone_id, protected_zone_id); - out.protectedZoneID = new ProtectedZoneID_t(protected_zone_id); + out.protectedZoneID = (ProtectedZoneID_t*) calloc(1, sizeof(ProtectedZoneID_t)); + toStruct_ProtectedZoneID(in.protected_zone_id, *out.protectedZoneID); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h index 44b51e993..f0c8319d7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF ProtectedCommunicationZonesRSU -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedCommunicationZonesRSU(const ProtectedCommunicationZonesRSU_t& in, denm_msgs::ProtectedCommunicationZonesRSU& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::ProtectedCommunicationZone array; - toRos_ProtectedCommunicationZone(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::ProtectedCommunicationZone el; + toRos_ProtectedCommunicationZone(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_ProtectedCommunicationZonesRSU(const denm_msgs::ProtectedCommunicationZonesRSU& in, ProtectedCommunicationZonesRSU_t& out) { - memset(&out, 0, sizeof(ProtectedCommunicationZonesRSU_t)); - for (int i = 0; i < in.array.size(); i++) { - ProtectedCommunicationZone_t array; - toStruct_ProtectedCommunicationZone(in.array[i], array); - ProtectedCommunicationZone_t* array_ptr = new ProtectedCommunicationZone_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ProtectedCommunicationZone_t* el = (ProtectedCommunicationZone_t*) calloc(1, sizeof(ProtectedCommunicationZone_t)); + toStruct_ProtectedCommunicationZone(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h index 9e16ae02e..8360f9dde 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER ProtectedZoneID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedZoneID(const ProtectedZoneID_t& in, denm_msgs::ProtectedZoneID& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneID(const denm_msgs::ProtectedZoneID& in, ProtectedZoneID_t& out) { - memset(&out, 0, sizeof(ProtectedZoneID_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h index 8b70322a0..2e3dfa506 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER ProtectedZoneRadius -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedZoneRadius(const ProtectedZoneRadius_t& in, denm_msgs::ProtectedZoneRadius& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneRadius(const denm_msgs::ProtectedZoneRadius& in, ProtectedZoneRadius_t& out) { - memset(&out, 0, sizeof(ProtectedZoneRadius_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h index 8d88b9532..261cfb6e4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED ProtectedZoneType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedZoneType(const ProtectedZoneType_t& in, denm_msgs::ProtectedZoneType& out) { - out.value = in; } void toStruct_ProtectedZoneType(const denm_msgs::ProtectedZoneType& in, ProtectedZoneType_t& out) { - memset(&out, 0, sizeof(ProtectedZoneType_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index e1e19687b..27a6141b1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE PtActivation -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PtActivation(const PtActivation_t& in, denm_msgs::PtActivation& out) { - toRos_PtActivationType(in.ptActivationType, out.pt_activation_type); toRos_PtActivationData(in.ptActivationData, out.pt_activation_data); } void toStruct_PtActivation(const denm_msgs::PtActivation& in, PtActivation_t& out) { - memset(&out, 0, sizeof(PtActivation_t)); toStruct_PtActivationType(in.pt_activation_type, out.ptActivationType); toStruct_PtActivationData(in.pt_activation_data, out.ptActivationData); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h index 8620cac77..42c352f5b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// OCTET-STRING PtActivationData -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PtActivationData(const PtActivationData_t& in, denm_msgs::PtActivationData& out) { - etsi_its_primitives_conversion::toRos_OCTET_STRING(in, out.value); } void toStruct_PtActivationData(const denm_msgs::PtActivationData& in, PtActivationData_t& out) { - memset(&out, 0, sizeof(PtActivationData_t)); + etsi_its_primitives_conversion::toStruct_OCTET_STRING(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h index 86f4531e7..864d7fe34 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER PtActivationType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PtActivationType(const PtActivationType_t& in, denm_msgs::PtActivationType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PtActivationType(const denm_msgs::PtActivationType& in, PtActivationType_t& out) { - memset(&out, 0, sizeof(PtActivationType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index 4e866b52e..dc482fd2f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF ReferenceDenms -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ReferenceDenms(const ReferenceDenms_t& in, denm_msgs::ReferenceDenms& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::ActionID array; - toRos_ActionID(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::ActionID el; + toRos_ActionID(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_ReferenceDenms(const denm_msgs::ReferenceDenms& in, ReferenceDenms_t& out) { - memset(&out, 0, sizeof(ReferenceDenms_t)); - for (int i = 0; i < in.array.size(); i++) { - ActionID_t array; - toStruct_ActionID(in.array[i], array); - ActionID_t* array_ptr = new ActionID_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + ActionID_t* el = (ActionID_t*) calloc(1, sizeof(ActionID_t)); + toStruct_ActionID(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index 75c5434b0..faa4c47d1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE ReferencePosition -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,7 +22,6 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ReferencePosition(const ReferencePosition_t& in, denm_msgs::ReferencePosition& out) { - toRos_Latitude(in.latitude, out.latitude); toRos_Longitude(in.longitude, out.longitude); toRos_PosConfidenceEllipse(in.positionConfidenceEllipse, out.position_confidence_ellipse); @@ -51,7 +29,6 @@ void toRos_ReferencePosition(const ReferencePosition_t& in, denm_msgs::Reference } void toStruct_ReferencePosition(const denm_msgs::ReferencePosition& in, ReferencePosition_t& out) { - memset(&out, 0, sizeof(ReferencePosition_t)); toStruct_Latitude(in.latitude, out.latitude); @@ -60,4 +37,4 @@ void toStruct_ReferencePosition(const denm_msgs::ReferencePosition& in, Referenc toStruct_Altitude(in.altitude, out.altitude); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h index 07d698e4a..85c0b8352 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RelevanceDistance -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RelevanceDistance(const RelevanceDistance_t& in, denm_msgs::RelevanceDistance& out) { - out.value = in; } void toStruct_RelevanceDistance(const denm_msgs::RelevanceDistance& in, RelevanceDistance_t& out) { - memset(&out, 0, sizeof(RelevanceDistance_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h index 5a0e2806c..9b644ce36 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RelevanceTrafficDirection -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RelevanceTrafficDirection(const RelevanceTrafficDirection_t& in, denm_msgs::RelevanceTrafficDirection& out) { - out.value = in; } void toStruct_RelevanceTrafficDirection(const denm_msgs::RelevanceTrafficDirection& in, RelevanceTrafficDirection_t& out) { - memset(&out, 0, sizeof(RelevanceTrafficDirection_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h index 6cf6f6e73..0873dc736 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RequestResponseIndication -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RequestResponseIndication(const RequestResponseIndication_t& in, denm_msgs::RequestResponseIndication& out) { - out.value = in; } void toStruct_RequestResponseIndication(const denm_msgs::RequestResponseIndication& in, RequestResponseIndication_t& out) { - memset(&out, 0, sizeof(RequestResponseIndication_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index c0fbbca09..453af4c6e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER RescueAndRecoveryWorkInProgressSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RescueAndRecoveryWorkInProgressSubCauseCode(const RescueAndRecoveryWorkInProgressSubCauseCode_t& in, denm_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RescueAndRecoveryWorkInProgressSubCauseCode(const denm_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& in, RescueAndRecoveryWorkInProgressSubCauseCode_t& out) { - memset(&out, 0, sizeof(RescueAndRecoveryWorkInProgressSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h index 53159e602..7bd6d7a39 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF RestrictedTypes -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RestrictedTypes(const RestrictedTypes_t& in, denm_msgs::RestrictedTypes& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::StationType array; - toRos_StationType(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::StationType el; + toRos_StationType(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_RestrictedTypes(const denm_msgs::RestrictedTypes& in, RestrictedTypes_t& out) { - memset(&out, 0, sizeof(RestrictedTypes_t)); - for (int i = 0; i < in.array.size(); i++) { - StationType_t array; - toStruct_StationType(in.array[i], array); - StationType_t* array_ptr = new StationType_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + StationType_t* el = (StationType_t*) calloc(1, sizeof(StationType_t)); + toStruct_StationType(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h index b348ad988..aaa981d50 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED RoadType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RoadType(const RoadType_t& in, denm_msgs::RoadType& out) { - out.value = in; } void toStruct_RoadType(const denm_msgs::RoadType& in, RoadType_t& out) { - memset(&out, 0, sizeof(RoadType_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index f182aaff0..e65fb8277 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE RoadWorksContainerExtended -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -48,112 +27,83 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RoadWorksContainerExtended(const RoadWorksContainerExtended_t& in, denm_msgs::RoadWorksContainerExtended& out) { - if (in.lightBarSirenInUse) { toRos_LightBarSirenInUse(*in.lightBarSirenInUse, out.light_bar_siren_in_use); out.light_bar_siren_in_use_is_present = true; } - if (in.closedLanes) { toRos_ClosedLanes(*in.closedLanes, out.closed_lanes); out.closed_lanes_is_present = true; } - if (in.restriction) { toRos_RestrictedTypes(*in.restriction, out.restriction); out.restriction_is_present = true; } - if (in.speedLimit) { toRos_SpeedLimit(*in.speedLimit, out.speed_limit); out.speed_limit_is_present = true; } - if (in.incidentIndication) { toRos_CauseCode(*in.incidentIndication, out.incident_indication); out.incident_indication_is_present = true; } - if (in.recommendedPath) { toRos_ItineraryPath(*in.recommendedPath, out.recommended_path); out.recommended_path_is_present = true; } - if (in.startingPointSpeedLimit) { toRos_DeltaReferencePosition(*in.startingPointSpeedLimit, out.starting_point_speed_limit); out.starting_point_speed_limit_is_present = true; } - if (in.trafficFlowRule) { toRos_TrafficRule(*in.trafficFlowRule, out.traffic_flow_rule); out.traffic_flow_rule_is_present = true; } - if (in.referenceDenms) { toRos_ReferenceDenms(*in.referenceDenms, out.reference_denms); out.reference_denms_is_present = true; } - } void toStruct_RoadWorksContainerExtended(const denm_msgs::RoadWorksContainerExtended& in, RoadWorksContainerExtended_t& out) { - memset(&out, 0, sizeof(RoadWorksContainerExtended_t)); if (in.light_bar_siren_in_use_is_present) { - LightBarSirenInUse_t light_bar_siren_in_use; - toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, light_bar_siren_in_use); - out.lightBarSirenInUse = new LightBarSirenInUse_t(light_bar_siren_in_use); + out.lightBarSirenInUse = (LightBarSirenInUse_t*) calloc(1, sizeof(LightBarSirenInUse_t)); + toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, *out.lightBarSirenInUse); } - if (in.closed_lanes_is_present) { - ClosedLanes_t closed_lanes; - toStruct_ClosedLanes(in.closed_lanes, closed_lanes); - out.closedLanes = new ClosedLanes_t(closed_lanes); + out.closedLanes = (ClosedLanes_t*) calloc(1, sizeof(ClosedLanes_t)); + toStruct_ClosedLanes(in.closed_lanes, *out.closedLanes); } - if (in.restriction_is_present) { - RestrictedTypes_t restriction; - toStruct_RestrictedTypes(in.restriction, restriction); - out.restriction = new RestrictedTypes_t(restriction); + out.restriction = (RestrictedTypes_t*) calloc(1, sizeof(RestrictedTypes_t)); + toStruct_RestrictedTypes(in.restriction, *out.restriction); } - if (in.speed_limit_is_present) { - SpeedLimit_t speed_limit; - toStruct_SpeedLimit(in.speed_limit, speed_limit); - out.speedLimit = new SpeedLimit_t(speed_limit); + out.speedLimit = (SpeedLimit_t*) calloc(1, sizeof(SpeedLimit_t)); + toStruct_SpeedLimit(in.speed_limit, *out.speedLimit); } - if (in.incident_indication_is_present) { - CauseCode_t incident_indication; - toStruct_CauseCode(in.incident_indication, incident_indication); - out.incidentIndication = new CauseCode_t(incident_indication); + out.incidentIndication = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); + toStruct_CauseCode(in.incident_indication, *out.incidentIndication); } - if (in.recommended_path_is_present) { - ItineraryPath_t recommended_path; - toStruct_ItineraryPath(in.recommended_path, recommended_path); - out.recommendedPath = new ItineraryPath_t(recommended_path); + out.recommendedPath = (ItineraryPath_t*) calloc(1, sizeof(ItineraryPath_t)); + toStruct_ItineraryPath(in.recommended_path, *out.recommendedPath); } - if (in.starting_point_speed_limit_is_present) { - DeltaReferencePosition_t starting_point_speed_limit; - toStruct_DeltaReferencePosition(in.starting_point_speed_limit, starting_point_speed_limit); - out.startingPointSpeedLimit = new DeltaReferencePosition_t(starting_point_speed_limit); + out.startingPointSpeedLimit = (DeltaReferencePosition_t*) calloc(1, sizeof(DeltaReferencePosition_t)); + toStruct_DeltaReferencePosition(in.starting_point_speed_limit, *out.startingPointSpeedLimit); } - if (in.traffic_flow_rule_is_present) { - TrafficRule_t traffic_flow_rule; - toStruct_TrafficRule(in.traffic_flow_rule, traffic_flow_rule); - out.trafficFlowRule = new TrafficRule_t(traffic_flow_rule); + out.trafficFlowRule = (TrafficRule_t*) calloc(1, sizeof(TrafficRule_t)); + toStruct_TrafficRule(in.traffic_flow_rule, *out.trafficFlowRule); } - if (in.reference_denms_is_present) { - ReferenceDenms_t reference_denms; - toStruct_ReferenceDenms(in.reference_denms, reference_denms); - out.referenceDenms = new ReferenceDenms_t(reference_denms); + out.referenceDenms = (ReferenceDenms_t*) calloc(1, sizeof(ReferenceDenms_t)); + toStruct_ReferenceDenms(in.reference_denms, *out.referenceDenms); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h index fedfed25d..80f4b3185 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER RoadworksSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RoadworksSubCauseCode(const RoadworksSubCauseCode_t& in, denm_msgs::RoadworksSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RoadworksSubCauseCode(const denm_msgs::RoadworksSubCauseCode& in, RoadworksSubCauseCode_t& out) { - memset(&out, 0, sizeof(RoadworksSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h index 32c58d57e..c6090fee3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SemiAxisLength -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SemiAxisLength(const SemiAxisLength_t& in, denm_msgs::SemiAxisLength& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SemiAxisLength(const denm_msgs::SemiAxisLength& in, SemiAxisLength_t& out) { - memset(&out, 0, sizeof(SemiAxisLength_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h index fca5a9ec7..0baf8b5e6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SequenceNumber -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SequenceNumber(const SequenceNumber_t& in, denm_msgs::SequenceNumber& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SequenceNumber(const denm_msgs::SequenceNumber& in, SequenceNumber_t& out) { - memset(&out, 0, sizeof(SequenceNumber_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h index baed8b737..f3da90978 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SignalViolationSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SignalViolationSubCauseCode(const SignalViolationSubCauseCode_t& in, denm_msgs::SignalViolationSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SignalViolationSubCauseCode(const denm_msgs::SignalViolationSubCauseCode& in, SignalViolationSubCauseCode_t& out) { - memset(&out, 0, sizeof(SignalViolationSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index a205c9d61..a92397833 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE SituationContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -43,39 +22,31 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SituationContainer(const SituationContainer_t& in, denm_msgs::SituationContainer& out) { - toRos_InformationQuality(in.informationQuality, out.information_quality); toRos_CauseCode(in.eventType, out.event_type); if (in.linkedCause) { toRos_CauseCode(*in.linkedCause, out.linked_cause); out.linked_cause_is_present = true; } - if (in.eventHistory) { toRos_EventHistory(*in.eventHistory, out.event_history); out.event_history_is_present = true; } - } void toStruct_SituationContainer(const denm_msgs::SituationContainer& in, SituationContainer_t& out) { - memset(&out, 0, sizeof(SituationContainer_t)); toStruct_InformationQuality(in.information_quality, out.informationQuality); toStruct_CauseCode(in.event_type, out.eventType); if (in.linked_cause_is_present) { - CauseCode_t linked_cause; - toStruct_CauseCode(in.linked_cause, linked_cause); - out.linkedCause = new CauseCode_t(linked_cause); + out.linkedCause = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); + toStruct_CauseCode(in.linked_cause, *out.linkedCause); } - if (in.event_history_is_present) { - EventHistory_t event_history; - toStruct_EventHistory(in.event_history, event_history); - out.eventHistory = new EventHistory_t(event_history); + out.eventHistory = (EventHistory_t*) calloc(1, sizeof(EventHistory_t)); + toStruct_EventHistory(in.event_history, *out.eventHistory); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h index b91039d8d..a8f84e92c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SlowVehicleSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SlowVehicleSubCauseCode(const SlowVehicleSubCauseCode_t& in, denm_msgs::SlowVehicleSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SlowVehicleSubCauseCode(const denm_msgs::SlowVehicleSubCauseCode& in, SlowVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(SlowVehicleSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h index aa8b49238..22757aa89 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// BIT-STRING SpecialTransportType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,16 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpecialTransportType(const SpecialTransportType_t& in, denm_msgs::SpecialTransportType& out) { - etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_SpecialTransportType(const denm_msgs::SpecialTransportType& in, SpecialTransportType_t& out) { - memset(&out, 0, sizeof(SpecialTransportType_t)); + etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index cc36d1058..0dcdd50b5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE Speed -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Speed(const Speed_t& in, denm_msgs::Speed& out) { - toRos_SpeedValue(in.speedValue, out.speed_value); toRos_SpeedConfidence(in.speedConfidence, out.speed_confidence); } void toStruct_Speed(const denm_msgs::Speed& in, Speed_t& out) { - memset(&out, 0, sizeof(Speed_t)); toStruct_SpeedValue(in.speed_value, out.speedValue); toStruct_SpeedConfidence(in.speed_confidence, out.speedConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h index 7f54bb247..46fe8fa2a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SpeedConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpeedConfidence(const SpeedConfidence_t& in, denm_msgs::SpeedConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedConfidence(const denm_msgs::SpeedConfidence& in, SpeedConfidence_t& out) { - memset(&out, 0, sizeof(SpeedConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h index 8d81fd8d6..4f854bdaf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SpeedLimit -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpeedLimit(const SpeedLimit_t& in, denm_msgs::SpeedLimit& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedLimit(const denm_msgs::SpeedLimit& in, SpeedLimit_t& out) { - memset(&out, 0, sizeof(SpeedLimit_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h index 5763175be..10467171f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SpeedValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpeedValue(const SpeedValue_t& in, denm_msgs::SpeedValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedValue(const denm_msgs::SpeedValue& in, SpeedValue_t& out) { - memset(&out, 0, sizeof(SpeedValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h index a9c582d93..42aafcbaf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER StationID -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationID(const StationID_t& in, denm_msgs::StationID& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationID(const denm_msgs::StationID& in, StationID_t& out) { - memset(&out, 0, sizeof(StationID_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h index eb342c4df..7227c4e59 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER StationType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationType(const StationType_t& in, denm_msgs::StationType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationType(const denm_msgs::StationType& in, StationType_t& out) { - memset(&out, 0, sizeof(StationType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h index 2ca20090a..136527453 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED StationarySince -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationarySince(const StationarySince_t& in, denm_msgs::StationarySince& out) { - out.value = in; } void toStruct_StationarySince(const denm_msgs::StationarySince& in, StationarySince_t& out) { - memset(&out, 0, sizeof(StationarySince_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index c20bcc9d6..9b0f0bb1e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE StationaryVehicleContainer -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -45,79 +24,59 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationaryVehicleContainer(const StationaryVehicleContainer_t& in, denm_msgs::StationaryVehicleContainer& out) { - if (in.stationarySince) { toRos_StationarySince(*in.stationarySince, out.stationary_since); out.stationary_since_is_present = true; } - if (in.stationaryCause) { toRos_CauseCode(*in.stationaryCause, out.stationary_cause); out.stationary_cause_is_present = true; } - if (in.carryingDangerousGoods) { toRos_DangerousGoodsExtended(*in.carryingDangerousGoods, out.carrying_dangerous_goods); out.carrying_dangerous_goods_is_present = true; } - if (in.numberOfOccupants) { toRos_NumberOfOccupants(*in.numberOfOccupants, out.number_of_occupants); out.number_of_occupants_is_present = true; } - if (in.vehicleIdentification) { toRos_VehicleIdentification(*in.vehicleIdentification, out.vehicle_identification); out.vehicle_identification_is_present = true; } - if (in.energyStorageType) { toRos_EnergyStorageType(*in.energyStorageType, out.energy_storage_type); out.energy_storage_type_is_present = true; } - } void toStruct_StationaryVehicleContainer(const denm_msgs::StationaryVehicleContainer& in, StationaryVehicleContainer_t& out) { - memset(&out, 0, sizeof(StationaryVehicleContainer_t)); if (in.stationary_since_is_present) { - StationarySince_t stationary_since; - toStruct_StationarySince(in.stationary_since, stationary_since); - out.stationarySince = new StationarySince_t(stationary_since); + out.stationarySince = (StationarySince_t*) calloc(1, sizeof(StationarySince_t)); + toStruct_StationarySince(in.stationary_since, *out.stationarySince); } - if (in.stationary_cause_is_present) { - CauseCode_t stationary_cause; - toStruct_CauseCode(in.stationary_cause, stationary_cause); - out.stationaryCause = new CauseCode_t(stationary_cause); + out.stationaryCause = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); + toStruct_CauseCode(in.stationary_cause, *out.stationaryCause); } - if (in.carrying_dangerous_goods_is_present) { - DangerousGoodsExtended_t carrying_dangerous_goods; - toStruct_DangerousGoodsExtended(in.carrying_dangerous_goods, carrying_dangerous_goods); - out.carryingDangerousGoods = new DangerousGoodsExtended_t(carrying_dangerous_goods); + out.carryingDangerousGoods = (DangerousGoodsExtended_t*) calloc(1, sizeof(DangerousGoodsExtended_t)); + toStruct_DangerousGoodsExtended(in.carrying_dangerous_goods, *out.carryingDangerousGoods); } - if (in.number_of_occupants_is_present) { - NumberOfOccupants_t number_of_occupants; - toStruct_NumberOfOccupants(in.number_of_occupants, number_of_occupants); - out.numberOfOccupants = new NumberOfOccupants_t(number_of_occupants); + out.numberOfOccupants = (NumberOfOccupants_t*) calloc(1, sizeof(NumberOfOccupants_t)); + toStruct_NumberOfOccupants(in.number_of_occupants, *out.numberOfOccupants); } - if (in.vehicle_identification_is_present) { - VehicleIdentification_t vehicle_identification; - toStruct_VehicleIdentification(in.vehicle_identification, vehicle_identification); - out.vehicleIdentification = new VehicleIdentification_t(vehicle_identification); + out.vehicleIdentification = (VehicleIdentification_t*) calloc(1, sizeof(VehicleIdentification_t)); + toStruct_VehicleIdentification(in.vehicle_identification, *out.vehicleIdentification); } - if (in.energy_storage_type_is_present) { - EnergyStorageType_t energy_storage_type; - toStruct_EnergyStorageType(in.energy_storage_type, energy_storage_type); - out.energyStorageType = new EnergyStorageType_t(energy_storage_type); + out.energyStorageType = (EnergyStorageType_t*) calloc(1, sizeof(EnergyStorageType_t)); + toStruct_EnergyStorageType(in.energy_storage_type, *out.energyStorageType); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h index 881ef8358..816bb1909 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER StationaryVehicleSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationaryVehicleSubCauseCode(const StationaryVehicleSubCauseCode_t& in, denm_msgs::StationaryVehicleSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationaryVehicleSubCauseCode(const denm_msgs::StationaryVehicleSubCauseCode& in, StationaryVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(StationaryVehicleSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index 375fc3525..4e7c4543a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE SteeringWheelAngle -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SteeringWheelAngle(const SteeringWheelAngle_t& in, denm_msgs::SteeringWheelAngle& out) { - toRos_SteeringWheelAngleValue(in.steeringWheelAngleValue, out.steering_wheel_angle_value); toRos_SteeringWheelAngleConfidence(in.steeringWheelAngleConfidence, out.steering_wheel_angle_confidence); } void toStruct_SteeringWheelAngle(const denm_msgs::SteeringWheelAngle& in, SteeringWheelAngle_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngle_t)); toStruct_SteeringWheelAngleValue(in.steering_wheel_angle_value, out.steeringWheelAngleValue); toStruct_SteeringWheelAngleConfidence(in.steering_wheel_angle_confidence, out.steeringWheelAngleConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h index 75eb8ba84..ce30e3734 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SteeringWheelAngleConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SteeringWheelAngleConfidence(const SteeringWheelAngleConfidence_t& in, denm_msgs::SteeringWheelAngleConfidence& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleConfidence(const denm_msgs::SteeringWheelAngleConfidence& in, SteeringWheelAngleConfidence_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleConfidence_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h index 37fc7478f..9d2ff11da 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SteeringWheelAngleValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SteeringWheelAngleValue(const SteeringWheelAngleValue_t& in, denm_msgs::SteeringWheelAngleValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleValue(const denm_msgs::SteeringWheelAngleValue& in, SteeringWheelAngleValue_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h index e9966ae07..b86ab2bea 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER SubCauseCodeType -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SubCauseCodeType(const SubCauseCodeType_t& in, denm_msgs::SubCauseCodeType& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SubCauseCodeType(const denm_msgs::SubCauseCodeType& in, SubCauseCodeType_t& out) { - memset(&out, 0, sizeof(SubCauseCodeType_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h index c6f404344..542222b5d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER Temperature -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Temperature(const Temperature_t& in, denm_msgs::Temperature& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Temperature(const denm_msgs::Temperature& in, Temperature_t& out) { - memset(&out, 0, sizeof(Temperature_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h index dece171c0..4d11e8772 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED Termination -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Termination(const Termination_t& in, denm_msgs::Termination& out) { - out.value = in; } void toStruct_Termination(const denm_msgs::Termination& in, Termination_t& out) { - memset(&out, 0, sizeof(Termination_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h index 5a65f5e99..77b8052a9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TimestampIts -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TimestampIts(const TimestampIts_t& in, denm_msgs::TimestampIts& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TimestampIts(const denm_msgs::TimestampIts& in, TimestampIts_t& out) { - memset(&out, 0, sizeof(TimestampIts_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index dfc4e9173..1126b25e8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -1,43 +1,17 @@ -/** ============================================================================ -MIT License +//// SEQUENCE-OF Traces -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once #include -#include #include -#include +#include #include #ifdef ROS1 -#include #include namespace denm_msgs = etsi_its_denm_msgs; #else -#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -46,27 +20,21 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Traces(const Traces_t& in, denm_msgs::Traces& out) { - - for (int i = 0; i < in.list.count; i++) { - denm_msgs::PathHistory array; - toRos_PathHistory(*(in.list.array[i]), array); - out.array.push_back(array); + for (int i = 0; i < in.list.count; ++i) { + denm_msgs::PathHistory el; + toRos_PathHistory(*(in.list.array[i]), el); + out.array.push_back(el); } - } void toStruct_Traces(const denm_msgs::Traces& in, Traces_t& out) { - memset(&out, 0, sizeof(Traces_t)); - for (int i = 0; i < in.array.size(); i++) { - PathHistory_t array; - toStruct_PathHistory(in.array[i], array); - PathHistory_t* array_ptr = new PathHistory_t(array); - int status = asn_sequence_add(&out, array_ptr); - if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); ++i) { + PathHistory_t* el = (PathHistory_t*) calloc(1, sizeof(PathHistory_t)); + toStruct_PathHistory(in.array[i], *el); + if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h index 59ebad3a5..3d4a228bd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TrafficConditionSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TrafficConditionSubCauseCode(const TrafficConditionSubCauseCode_t& in, denm_msgs::TrafficConditionSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TrafficConditionSubCauseCode(const denm_msgs::TrafficConditionSubCauseCode& in, TrafficConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(TrafficConditionSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h index e5b035043..1edf243a9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED TrafficRule -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TrafficRule(const TrafficRule_t& in, denm_msgs::TrafficRule& out) { - out.value = in; } void toStruct_TrafficRule(const denm_msgs::TrafficRule& in, TrafficRule_t& out) { - memset(&out, 0, sizeof(TrafficRule_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h index 6af97b08a..1ed85aaec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TransmissionInterval -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TransmissionInterval(const TransmissionInterval_t& in, denm_msgs::TransmissionInterval& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TransmissionInterval(const denm_msgs::TransmissionInterval& in, TransmissionInterval_t& out) { - memset(&out, 0, sizeof(TransmissionInterval_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h index 5a2095107..bdb223ee8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER TurningRadius -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TurningRadius(const TurningRadius_t& in, denm_msgs::TurningRadius& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TurningRadius(const denm_msgs::TurningRadius& in, TurningRadius_t& out) { - memset(&out, 0, sizeof(TurningRadius_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h index 80c8cd0a2..5804229c1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// IA5String VDS -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VDS(const VDS_t& in, denm_msgs::VDS& out) { - etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_VDS(const denm_msgs::VDS& in, VDS_t& out) { - memset(&out, 0, sizeof(VDS_t)); + etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h index 3c0add6f5..15b2f7cbb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER ValidityDuration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ValidityDuration(const ValidityDuration_t& in, denm_msgs::ValidityDuration& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ValidityDuration(const denm_msgs::ValidityDuration& in, ValidityDuration_t& out) { - memset(&out, 0, sizeof(ValidityDuration_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h index d78e2f406..eeb1089c1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleBreakdownSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleBreakdownSubCauseCode(const VehicleBreakdownSubCauseCode_t& in, denm_msgs::VehicleBreakdownSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleBreakdownSubCauseCode(const denm_msgs::VehicleBreakdownSubCauseCode& in, VehicleBreakdownSubCauseCode_t& out) { - memset(&out, 0, sizeof(VehicleBreakdownSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index 617bc4d1c..6ab983ebe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE VehicleIdentification -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,35 +20,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleIdentification(const VehicleIdentification_t& in, denm_msgs::VehicleIdentification& out) { - if (in.wMInumber) { - toRos_WMInumber(*in.wMInumber, out.wm_inumber); - out.wm_inumber_is_present = true; + toRos_WMInumber(*in.wMInumber, out.w_m_inumber); + out.w_m_inumber_is_present = true; } - if (in.vDS) { - toRos_VDS(*in.vDS, out.vds); - out.vds_is_present = true; + toRos_VDS(*in.vDS, out.v_ds); + out.v_ds_is_present = true; } - } void toStruct_VehicleIdentification(const denm_msgs::VehicleIdentification& in, VehicleIdentification_t& out) { - memset(&out, 0, sizeof(VehicleIdentification_t)); - if (in.wm_inumber_is_present) { - WMInumber_t wm_inumber; - toStruct_WMInumber(in.wm_inumber, wm_inumber); - out.wMInumber = new WMInumber_t(wm_inumber); + if (in.w_m_inumber_is_present) { + out.wMInumber = (WMInumber_t*) calloc(1, sizeof(WMInumber_t)); + toStruct_WMInumber(in.w_m_inumber, *out.wMInumber); } - - if (in.vds_is_present) { - VDS_t vds; - toStruct_VDS(in.vds, vds); - out.vDS = new VDS_t(vds); + if (in.v_ds_is_present) { + out.vDS = (VDS_t*) calloc(1, sizeof(VDS_t)); + toStruct_VDS(in.v_ds, *out.vDS); } - } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index a22de9500..821a114a3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE VehicleLength -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleLength(const VehicleLength_t& in, denm_msgs::VehicleLength& out) { - toRos_VehicleLengthValue(in.vehicleLengthValue, out.vehicle_length_value); toRos_VehicleLengthConfidenceIndication(in.vehicleLengthConfidenceIndication, out.vehicle_length_confidence_indication); } void toStruct_VehicleLength(const denm_msgs::VehicleLength& in, VehicleLength_t& out) { - memset(&out, 0, sizeof(VehicleLength_t)); toStruct_VehicleLengthValue(in.vehicle_length_value, out.vehicleLengthValue); toStruct_VehicleLengthConfidenceIndication(in.vehicle_length_confidence_indication, out.vehicleLengthConfidenceIndication); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h index a489a6494..14ed9a8a8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED VehicleLengthConfidenceIndication -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleLengthConfidenceIndication(const VehicleLengthConfidenceIndication_t& in, denm_msgs::VehicleLengthConfidenceIndication& out) { - out.value = in; } void toStruct_VehicleLengthConfidenceIndication(const denm_msgs::VehicleLengthConfidenceIndication& in, VehicleLengthConfidenceIndication_t& out) { - memset(&out, 0, sizeof(VehicleLengthConfidenceIndication_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h index 63d619b7b..aec4c2df7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleLengthValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleLengthValue(const VehicleLengthValue_t& in, denm_msgs::VehicleLengthValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleLengthValue(const denm_msgs::VehicleLengthValue& in, VehicleLengthValue_t& out) { - memset(&out, 0, sizeof(VehicleLengthValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h index a4939b863..65901d25f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleMass -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleMass(const VehicleMass_t& in, denm_msgs::VehicleMass& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleMass(const denm_msgs::VehicleMass& in, VehicleMass_t& out) { - memset(&out, 0, sizeof(VehicleMass_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h index 9fa69e3fe..9bd66ddfb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED VehicleRole -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleRole(const VehicleRole_t& in, denm_msgs::VehicleRole& out) { - out.value = in; } void toStruct_VehicleRole(const denm_msgs::VehicleRole& in, VehicleRole_t& out) { - memset(&out, 0, sizeof(VehicleRole_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h index 60605b632..04361bc52 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VehicleWidth -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleWidth(const VehicleWidth_t& in, denm_msgs::VehicleWidth& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleWidth(const denm_msgs::VehicleWidth& in, VehicleWidth_t& out) { - memset(&out, 0, sizeof(VehicleWidth_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index e7ef2b099..0e35794b4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE VerticalAcceleration -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VerticalAcceleration(const VerticalAcceleration_t& in, denm_msgs::VerticalAcceleration& out) { - toRos_VerticalAccelerationValue(in.verticalAccelerationValue, out.vertical_acceleration_value); toRos_AccelerationConfidence(in.verticalAccelerationConfidence, out.vertical_acceleration_confidence); } void toStruct_VerticalAcceleration(const denm_msgs::VerticalAcceleration& in, VerticalAcceleration_t& out) { - memset(&out, 0, sizeof(VerticalAcceleration_t)); toStruct_VerticalAccelerationValue(in.vertical_acceleration_value, out.verticalAccelerationValue); toStruct_AccelerationConfidence(in.vertical_acceleration_confidence, out.verticalAccelerationConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h index 03614cceb..7a773ba24 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER VerticalAccelerationValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VerticalAccelerationValue(const VerticalAccelerationValue_t& in, denm_msgs::VerticalAccelerationValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VerticalAccelerationValue(const denm_msgs::VerticalAccelerationValue& in, VerticalAccelerationValue_t& out) { - memset(&out, 0, sizeof(VerticalAccelerationValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h index 3986ca61d..b469faf90 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// IA5String WMInumber -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_WMInumber(const WMInumber_t& in, denm_msgs::WMInumber& out) { - etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_WMInumber(const denm_msgs::WMInumber& in, WMInumber_t& out) { - memset(&out, 0, sizeof(WMInumber_t)); + etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h index 4dd8c0735..f06439c6e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER WheelBaseVehicle -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_WheelBaseVehicle(const WheelBaseVehicle_t& in, denm_msgs::WheelBaseVehicle& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WheelBaseVehicle(const denm_msgs::WheelBaseVehicle& in, WheelBaseVehicle_t& out) { - memset(&out, 0, sizeof(WheelBaseVehicle_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h index fcdc94f8f..e974ab54e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER WrongWayDrivingSubCauseCode -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_WrongWayDrivingSubCauseCode(const WrongWayDrivingSubCauseCode_t& in, denm_msgs::WrongWayDrivingSubCauseCode& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WrongWayDrivingSubCauseCode(const denm_msgs::WrongWayDrivingSubCauseCode& in, WrongWayDrivingSubCauseCode_t& out) { - memset(&out, 0, sizeof(WrongWayDrivingSubCauseCode_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h index b84cf7f14..a1965ceaf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// SEQUENCE YawRate -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,17 +20,15 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_YawRate(const YawRate_t& in, denm_msgs::YawRate& out) { - toRos_YawRateValue(in.yawRateValue, out.yaw_rate_value); toRos_YawRateConfidence(in.yawRateConfidence, out.yaw_rate_confidence); } void toStruct_YawRate(const denm_msgs::YawRate& in, YawRate_t& out) { - memset(&out, 0, sizeof(YawRate_t)); toStruct_YawRateValue(in.yaw_rate_value, out.yawRateValue); toStruct_YawRateConfidence(in.yaw_rate_confidence, out.yawRateConfidence); } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h index 7f5306470..d93f80306 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h @@ -1,32 +1,12 @@ -/** ============================================================================ -MIT License +//// ENUMERATED YawRateConfidence -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include + #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -39,14 +19,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_YawRateConfidence(const YawRateConfidence_t& in, denm_msgs::YawRateConfidence& out) { - out.value = in; } void toStruct_YawRateConfidence(const denm_msgs::YawRateConfidence& in, YawRateConfidence_t& out) { - memset(&out, 0, sizeof(YawRateConfidence_t)); + out = in.value; } -} \ No newline at end of file +} diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h index 37493669e..f065249e0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h @@ -1,31 +1,10 @@ -/** ============================================================================ -MIT License +//// INTEGER YawRateValue -Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -============================================================================= */ - -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- #pragma once +#include + #include #include #include @@ -41,14 +20,13 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_YawRateValue(const YawRateValue_t& in, denm_msgs::YawRateValue& out) { - etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_YawRateValue(const denm_msgs::YawRateValue& in, YawRateValue_t& out) { - memset(&out, 0, sizeof(YawRateValue_t)); + etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} \ No newline at end of file +} diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg index 4a4e59cb3..9865b14b3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AccelerationConfidence ::= INTEGER {pointOneMeterPerSecSquared(1), outOfRange(101), unavailable(102)} (0 .. 102) -# ------------------------------------------------------------------------------ +## INTEGER AccelerationConfidence uint8 value + uint8 MIN = 0 uint8 MAX = 102 + uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg index e1729d637..4a7f9d5c5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg @@ -1,44 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AccelerationControl ::= BIT STRING { -# brakePedalEngaged (0), -# gasPedalEngaged (1), -# emergencyBrakeEngaged (2), -# collisionWarningEngaged (3), -# accEngaged (4), -# cruiseControlEngaged (5), -# speedLimiterEngaged (6) -# } (SIZE(7)) -# ------------------------------------------------------------------------------ +## BIT-STRING AccelerationControl uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 + uint8 BIT_INDEX_BRAKE_PEDAL_ENGAGED = 0 uint8 BIT_INDEX_GAS_PEDAL_ENGAGED = 1 uint8 BIT_INDEX_EMERGENCY_BRAKE_ENGAGED = 2 @@ -46,4 +11,3 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg index b09fec1ee..796d1b8b9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AccidentSubCauseCode ::= INTEGER {unavailable(0), multiVehicleAccident(1), heavyAccident(2), accidentInvolvingLorry(3), accidentInvolvingBus(4), accidentInvolvingHazardousMaterials(5), accidentOnOppositeLane(6), unsecuredAccident(7), assistanceRequested(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AccidentSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 MULTI_VEHICLE_ACCIDENT = 1 uint8 HEAVY_ACCIDENT = 2 @@ -40,4 +14,3 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg index 845afc0d2..20cb30ac9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ActionID ::= SEQUENCE { -# originatingStationID StationID, -# sequenceNumber SequenceNumber -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ActionID StationID originating_station_id + SequenceNumber sequence_number + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 54039db9b..8dfc404d6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-AdhesionSubCauseCode ::= INTEGER {unavailable(0), heavyFrostOnRoad(1), fuelOnRoad(2), mudOnRoad(3), snowOnRoad(4), iceOnRoad(5), blackIceOnRoad(6), oilOnRoad(7), looseChippings(8), instantBlackIce(9), roadsSalted(10)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionAdhesionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 HEAVY_FROST_ON_ROAD = 1 uint8 FUEL_ON_ROAD = 2 @@ -42,4 +16,3 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 0e9e5babd..5e8c226b8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-ExtremeWeatherConditionSubCauseCode ::= INTEGER {unavailable(0), strongWinds(1), damagingHail(2), hurricane(3), thunderstorm(4), tornado(5), blizzard(6)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 STRONG_WINDS = 1 uint8 DAMAGING_HAIL = 2 @@ -38,4 +12,3 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index 643edd4b2..b71e00a5b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-PrecipitationSubCauseCode ::= INTEGER {unavailable(0), heavyRain(1), heavySnowfall(2), softHail(3)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index cecf863ab..2914f7b84 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-VisibilitySubCauseCode ::= INTEGER {unavailable(0), fog(1), smoke(2), heavySnowfall(3), heavyRain(4), heavyHail(5), lowSunGlare(6), sandstorms(7), swarmsOfInsects(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionVisibilitySubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 FOG = 1 uint8 SMOKE = 2 @@ -40,4 +14,3 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg index 1e84f8bc4..ee0b01eb4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Altitude ::= SEQUENCE { -# altitudeValue AltitudeValue, -# altitudeConfidence AltitudeConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Altitude AltitudeValue altitude_value + AltitudeConfidence altitude_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg index 31c124195..e6081a967 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg @@ -1,49 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AltitudeConfidence ::= ENUMERATED { -# alt-000-01 (0), -# alt-000-02 (1), -# alt-000-05 (2), -# alt-000-10 (3), -# alt-000-20 (4), -# alt-000-50 (5), -# alt-001-00 (6), -# alt-002-00 (7), -# alt-005-00 (8), -# alt-010-00 (9), -# alt-020-00 (10), -# alt-050-00 (11), -# alt-100-00 (12), -# alt-200-00 (13), -# outOfRange (14), -# unavailable (15) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED AltitudeConfidence uint8 value uint8 ALT_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg index 404256f66..db7c77a3d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AltitudeValue ::= INTEGER {referenceEllipsoidSurface(0), oneCentimeter(1), unavailable(800001)} (-100000..800001) -# ------------------------------------------------------------------------------ +## INTEGER AltitudeValue int32 value + int32 MIN = -100000 int32 MAX = 800001 + int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg index b46724274..c716cd243 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg @@ -1,38 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# BasicContainer ::= SEQUENCE { -# stationType StationType, -# referencePosition ReferencePosition, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE BasicContainer .extensible StationType station_type + ReferencePosition reference_position + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg index adfc414f6..b5ac28ce2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg @@ -1,86 +1,61 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# BasicVehicleContainerHighFrequency ::= SEQUENCE { -# heading Heading, -# speed Speed, -# driveDirection DriveDirection, -# vehicleLength VehicleLength, -# vehicleWidth VehicleWidth, -# longitudinalAcceleration LongitudinalAcceleration, -# curvature Curvature, -# curvatureCalculationMode CurvatureCalculationMode, -# yawRate YawRate, -# accelerationControl AccelerationControl OPTIONAL, -# lanePosition LanePosition OPTIONAL, -# steeringWheelAngle SteeringWheelAngle OPTIONAL, -# lateralAcceleration LateralAcceleration OPTIONAL, -# verticalAcceleration VerticalAcceleration OPTIONAL, -# performanceClass PerformanceClass OPTIONAL, -# cenDsrcTollingZone CenDsrcTollingZone OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE BasicVehicleContainerHighFrequency Heading heading + Speed speed + DriveDirection drive_direction + VehicleLength vehicle_length + VehicleWidth vehicle_width + LongitudinalAcceleration longitudinal_acceleration + Curvature curvature + CurvatureCalculationMode curvature_calculation_mode + YawRate yaw_rate -AccelerationControl acceleration_control + bool acceleration_control_is_present +AccelerationControl acceleration_control + -LanePosition lane_position bool lane_position_is_present +LanePosition lane_position + -SteeringWheelAngle steering_wheel_angle bool steering_wheel_angle_is_present +SteeringWheelAngle steering_wheel_angle + -LateralAcceleration lateral_acceleration bool lateral_acceleration_is_present +LateralAcceleration lateral_acceleration + -VerticalAcceleration vertical_acceleration bool vertical_acceleration_is_present +VerticalAcceleration vertical_acceleration + -PerformanceClass performance_class bool performance_class_is_present +PerformanceClass performance_class + -CenDsrcTollingZone cen_dsrc_tolling_zone bool cen_dsrc_tolling_zone_is_present +CenDsrcTollingZone cen_dsrc_tolling_zone + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg index 8de9fb81a..a1d377741 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg @@ -1,40 +1,15 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# BasicVehicleContainerLowFrequency ::= SEQUENCE { -# vehicleRole VehicleRole, -# exteriorLights ExteriorLights, -# pathHistory PathHistory -# } -# ------------------------------------------------------------------------------ +## SEQUENCE BasicVehicleContainerLowFrequency VehicleRole vehicle_role + ExteriorLights exterior_lights + PathHistory path_history + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg index ba24c19b0..1af66c4c2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg @@ -1,37 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CAM ::= SEQUENCE { -# header ItsPduHeader, -# cam CoopAwareness -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CAM +# The root data frame for cooperative awareness messages ItsPduHeader header + CoopAwareness cam + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg index 99da1fd9f..d87f12a96 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg @@ -1,46 +1,20 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CamParameters ::= SEQUENCE { -# basicContainer BasicContainer, -# highFrequencyContainer HighFrequencyContainer, -# lowFrequencyContainer LowFrequencyContainer OPTIONAL, -# specialVehicleContainer SpecialVehicleContainer OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CamParameters .extensible BasicContainer basic_container + HighFrequencyContainer high_frequency_container -LowFrequencyContainer low_frequency_container + bool low_frequency_container_is_present +LowFrequencyContainer low_frequency_container + -SpecialVehicleContainer special_vehicle_container bool special_vehicle_container_is_present +SpecialVehicleContainer special_vehicle_container + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg index 13f0048db..e3fdccaff 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg @@ -1,38 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CauseCode ::= SEQUENCE { -# causeCode CauseCodeType, -# subCauseCode SubCauseCodeType, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CauseCode .extensible CauseCodeType cause_code + SubCauseCodeType sub_cause_code + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg index 1a2cc7175..172a0fc12 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg @@ -1,64 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CauseCodeType ::= INTEGER { -# reserved (0), -# trafficCondition (1), -# accident (2), -# roadworks (3), -# impassability (5), -# adverseWeatherCondition-Adhesion (6), -# aquaplannning (7), -# hazardousLocation-SurfaceCondition (9), -# hazardousLocation-ObstacleOnTheRoad (10), -# hazardousLocation-AnimalOnTheRoad (11), -# humanPresenceOnTheRoad (12), -# wrongWayDriving (14), -# rescueAndRecoveryWorkInProgress (15), -# adverseWeatherCondition-ExtremeWeatherCondition (17), -# adverseWeatherCondition-Visibility (18), -# adverseWeatherCondition-Precipitation (19), -# slowVehicle (26), -# dangerousEndOfQueue (27), -# vehicleBreakdown (91), -# postCrash (92), -# humanProblem (93), -# stationaryVehicle (94), -# emergencyVehicleApproaching (95), -# hazardousLocation-DangerousCurve (96), -# collisionRisk (97), -# signalViolation (98), -# dangerousSituation (99) -# } (0..255) -# ------------------------------------------------------------------------------ +## INTEGER CauseCodeType uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 RESERVED = 0 uint8 TRAFFIC_CONDITION = 1 uint8 ACCIDENT = 2 @@ -86,4 +32,3 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg index 39c0affef..449a28242 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg @@ -1,42 +1,16 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CenDsrcTollingZone ::= SEQUENCE { -# protectedZoneLatitude Latitude, -# protectedZoneLongitude Longitude, -# cenDsrcTollingZoneID CenDsrcTollingZoneID OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CenDsrcTollingZone .extensible Latitude protected_zone_latitude + Longitude protected_zone_longitude -CenDsrcTollingZoneID cen_dsrc_tolling_zone_id + bool cen_dsrc_tolling_zone_id_is_present +CenDsrcTollingZoneID cen_dsrc_tolling_zone_id + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg index 50b563c91..efb20a09e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg @@ -1,32 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CenDsrcTollingZoneID ::= ProtectedZoneID -# ------------------------------------------------------------------------------ +## TYPE-ALIAS CenDsrcTollingZoneID ProtectedZoneID value - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg index 4f4b22816..aec88d388 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg @@ -1,44 +1,18 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ClosedLanes ::= SEQUENCE { -# innerhardShoulderStatus HardShoulderStatus OPTIONAL, -# outerhardShoulderStatus HardShoulderStatus OPTIONAL, -# drivingLaneStatus DrivingLaneStatus OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ClosedLanes .extensible -HardShoulderStatus innerhard_shoulder_status bool innerhard_shoulder_status_is_present +HardShoulderStatus innerhard_shoulder_status + -HardShoulderStatus outerhard_shoulder_status bool outerhard_shoulder_status_is_present +HardShoulderStatus outerhard_shoulder_status + -DrivingLaneStatus driving_lane_status bool driving_lane_status_is_present +DrivingLaneStatus driving_lane_status + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg index cbd4d715a..f3afe70d0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CollisionRiskSubCauseCode ::= INTEGER {unavailable(0), longitudinalCollisionRisk(1), crossingCollisionRisk(2), lateralCollisionRisk(3), vulnerableRoadUser(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER CollisionRiskSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg index 78fc94758..a6304da16 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CoopAwareness ::= SEQUENCE { -# generationDeltaTime GenerationDeltaTime, -# camParameters CamParameters -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CoopAwareness GenerationDeltaTime generation_delta_time + CamParameters cam_parameters + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg index ac99ea8a4..21f001b6a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Curvature ::= SEQUENCE { -# curvatureValue CurvatureValue, -# curvatureConfidence CurvatureConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Curvature CurvatureValue curvature_value + CurvatureConfidence curvature_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg index 65473f0cb..d76cf7cdd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CurvatureCalculationMode ::= ENUMERATED {yawRateUsed(0), yawRateNotUsed(1), unavailable(2), ...} -# ------------------------------------------------------------------------------ +## ENUMERATED CurvatureCalculationMode .extensible uint8 value uint8 YAW_RATE_USED = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg index 56dea214e..17bbbf4de 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg @@ -1,41 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CurvatureConfidence ::= ENUMERATED { -# onePerMeter-0-00002 (0), -# onePerMeter-0-0001 (1), -# onePerMeter-0-0005 (2), -# onePerMeter-0-002 (3), -# onePerMeter-0-01 (4), -# onePerMeter-0-1 (5), -# outOfRange (6), -# unavailable (7) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED CurvatureConfidence uint8 value uint8 ONE_PER_METER_0_00002 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg index f3ce6a111..da3928552 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CurvatureValue ::= INTEGER {straight(0), unavailable(1023)} (-1023..1023) -# ------------------------------------------------------------------------------ +## INTEGER CurvatureValue int16 value + int16 MIN = -1023 int16 MAX = 1023 + int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index 4461c2203..b6d9d0329 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousEndOfQueueSubCauseCode ::= INTEGER {unavailable(0), suddenEndOfQueue(1), queueOverHill(2), queueAroundBend(3), queueInTunnel(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER DangerousEndOfQueueSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg index 44ae47a36..df3611bb6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg @@ -1,61 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousGoodsBasic::= ENUMERATED { -# explosives1(0), -# explosives2(1), -# explosives3(2), -# explosives4(3), -# explosives5(4), -# explosives6(5), -# flammableGases(6), -# nonFlammableGases(7), -# toxicGases(8), -# flammableLiquids(9), -# flammableSolids(10), -# substancesLiableToSpontaneousCombustion(11), -# substancesEmittingFlammableGasesUponContactWithWater(12), -# oxidizingSubstances(13), -# organicPeroxides(14), -# toxicSubstances(15), -# infectiousSubstances(16), -# radioactiveMaterial(17), -# corrosiveSubstances(18), -# miscellaneousDangerousSubstances(19) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED DangerousGoodsBasic uint8 value -uint8 EXPLOSIVES_1 = 0 -uint8 EXPLOSIVES_2 = 1 -uint8 EXPLOSIVES_3 = 2 -uint8 EXPLOSIVES_4 = 3 -uint8 EXPLOSIVES_5 = 4 -uint8 EXPLOSIVES_6 = 5 +uint8 EXPLOSIVES1 = 0 +uint8 EXPLOSIVES2 = 1 +uint8 EXPLOSIVES3 = 2 +uint8 EXPLOSIVES4 = 3 +uint8 EXPLOSIVES5 = 4 +uint8 EXPLOSIVES6 = 5 uint8 FLAMMABLE_GASES = 6 uint8 NON_FLAMMABLE_GASES = 7 uint8 TOXIC_GASES = 8 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg index ef0650e50..a04ff7a10 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg @@ -1,34 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## SEQUENCE DangerousGoodsContainer + +DangerousGoodsBasic dangerous_goods_basic + + -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousGoodsContainer ::= SEQUENCE { -# dangerousGoodsBasic DangerousGoodsBasic -# } -# ------------------------------------------------------------------------------ -DangerousGoodsBasic dangerous_goods_basic diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg index 1b059d622..577cba69f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg @@ -1,65 +1,36 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousGoodsExtended ::= SEQUENCE { -# dangerousGoodsType DangerousGoodsBasic, -# unNumber INTEGER (0..9999), -# elevatedTemperature BOOLEAN, -# tunnelsRestricted BOOLEAN, -# limitedQuantity BOOLEAN, -# emergencyActionCode IA5String (SIZE (1..24)) OPTIONAL, -# phoneNumber PhoneNumber OPTIONAL, -# companyName UTF8String (SIZE (1..24)) OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE DangerousGoodsExtended .extensible DangerousGoodsBasic dangerous_goods_type + uint16 un_number uint16 UN_NUMBER_MIN = 0 uint16 UN_NUMBER_MAX = 9999 bool elevated_temperature + bool tunnels_restricted + bool limited_quantity -string emergency_action_code + bool emergency_action_code_is_present -uint8 EMERGENCY_ACTION_CODE_MIN_SIZE = 1 -uint8 EMERGENCY_ACTION_CODE_MAX_SIZE = 24 +string emergency_action_code +uint8 EMERGENCY_ACTION_CODE_LENGTH_MIN = 1 +uint8 EMERGENCY_ACTION_CODE_LENGTH_MAX = 24 -PhoneNumber phone_number bool phone_number_is_present +PhoneNumber phone_number + -string company_name bool company_name_is_present -uint8 COMPANY_NAME_MIN_SIZE = 1 -uint8 COMPANY_NAME_MAX_SIZE = 24 +string company_name +uint8 COMPANY_NAME_LENGTH_MIN = 1 +uint8 COMPANY_NAME_LENGTH_MAX = 24 + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg index 742d6696b..5c1089ce4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousSituationSubCauseCode ::= INTEGER {unavailable(0), emergencyElectronicBrakeEngaged(1), preCrashSystemEngaged(2), espEngaged(3), absEngaged(4), aebEngaged(5), brakeWarningEngaged(6), collisionRiskWarningEngaged(7)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER DangerousSituationSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 EMERGENCY_ELECTRONIC_BRAKE_ENGAGED = 1 uint8 PRE_CRASH_SYSTEM_ENGAGED = 2 @@ -39,4 +13,3 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg index e8e7cd2c8..ed6cdfa42 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaAltitude ::= INTEGER {oneCentimeterUp (1), oneCentimeterDown (-1), unavailable(12800)} (-12700..12800) -# ------------------------------------------------------------------------------ +## INTEGER DeltaAltitude int16 value + int16 MIN = -12700 int16 MAX = 12800 + int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg index b4d53fc21..3aaa64597 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaLatitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10) , unavailable(131072)} (-131071..131072) -# ------------------------------------------------------------------------------ +## INTEGER DeltaLatitude int32 value + int32 MIN = -131071 int32 MAX = 131072 + int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg index 09e330c8d..1c61c7b4d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaLongitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(131072)} (-131071..131072) -# ------------------------------------------------------------------------------ +## INTEGER DeltaLongitude int32 value + int32 MIN = -131071 int32 MAX = 131072 + int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg index 687e6a5be..ce78e8e7d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg @@ -1,40 +1,15 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaReferencePosition ::= SEQUENCE { -# deltaLatitude DeltaLatitude, -# deltaLongitude DeltaLongitude, -# deltaAltitude DeltaAltitude -# } -# ------------------------------------------------------------------------------ +## SEQUENCE DeltaReferencePosition DeltaLatitude delta_latitude + DeltaLongitude delta_longitude + DeltaAltitude delta_altitude + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg index d66dfc374..ef631d52d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DigitalMap ::= SEQUENCE (SIZE(1..256)) OF ReferencePosition -# ------------------------------------------------------------------------------ +## SEQUENCE-OF DigitalMap ReferencePosition[] array -uint16 MIN_SIZE = 1 -uint16 MAX_SIZE = 256 - +uint16 LENGTH_MIN = 1 +uint16 LENGTH_MAX = 256 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg index 4bb4caf19..581ffa6dc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DriveDirection ::= ENUMERATED {forward (0), backward (1), unavailable (2)} -# ------------------------------------------------------------------------------ +## ENUMERATED DriveDirection uint8 value uint8 FORWARD = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg index 682d819d3..228db1255 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg @@ -1,35 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DrivingLaneStatus ::= BIT STRING (SIZE (1..13)) -# ------------------------------------------------------------------------------ +## BIT-STRING DrivingLaneStatus uint8[] value uint8 bits_unused -uint8 MIN_SIZE_BITS = 1 -uint8 MAX_SIZE_BITS = 13 +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 13 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg index 80ae25981..d529b3842 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg @@ -1,32 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmbarkationStatus ::= BOOLEAN -# ------------------------------------------------------------------------------ +## BOOLEAN EmbarkationStatus bool value - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg index c4b986317..c3405eac6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg @@ -1,42 +1,17 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmergencyContainer ::= SEQUENCE { -# lightBarSirenInUse LightBarSirenInUse, -# incidentIndication CauseCode OPTIONAL, -# emergencyPriority EmergencyPriority OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE EmergencyContainer LightBarSirenInUse light_bar_siren_in_use -CauseCode incident_indication + bool incident_indication_is_present +CauseCode incident_indication + -EmergencyPriority emergency_priority bool emergency_priority_is_present +EmergencyPriority emergency_priority + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg index 0d7afaae7..b80ba12a6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg @@ -1,36 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmergencyPriority ::= BIT STRING {requestForRightOfWay(0), requestForFreeCrossingAtATrafficLight(1)} (SIZE(2)) -# ------------------------------------------------------------------------------ +## BIT-STRING EmergencyPriority uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 + uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index d88a0b461..73bff4f9a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmergencyVehicleApproachingSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicleApproaching(1), prioritizedVehicleApproaching(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER EmergencyVehicleApproachingSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg index 104cabb0c..26e57dfde 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EnergyStorageType ::= BIT STRING {hydrogenStorage(0), electricEnergyStorage(1), liquidPropaneGas(2), compressedNaturalGas(3), diesel(4), gasoline(5), ammonia(6)} (SIZE(7)) -# ------------------------------------------------------------------------------ +## BIT-STRING EnergyStorageType uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 + uint8 BIT_INDEX_HYDROGEN_STORAGE = 0 uint8 BIT_INDEX_ELECTRIC_ENERGY_STORAGE = 1 uint8 BIT_INDEX_LIQUID_PROPANE_GAS = 2 @@ -38,4 +11,3 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg index e31ae24c9..be3e6559c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EventHistory::= SEQUENCE (SIZE(1..23)) OF EventPoint -# ------------------------------------------------------------------------------ +## SEQUENCE-OF EventHistory EventPoint[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 23 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 23 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg index c4f7df89c..bf18a2813 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg @@ -1,41 +1,16 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EventPoint ::= SEQUENCE { -# eventPosition DeltaReferencePosition, -# eventDeltaTime PathDeltaTime OPTIONAL, -# informationQuality InformationQuality -# } -# ------------------------------------------------------------------------------ +## SEQUENCE EventPoint DeltaReferencePosition event_position -PathDeltaTime event_delta_time + bool event_delta_time_is_present +PathDeltaTime event_delta_time + InformationQuality information_quality + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg index ce43d902b..957ddc36b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg @@ -1,45 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ExteriorLights ::= BIT STRING { -# lowBeamHeadlightsOn (0), -# highBeamHeadlightsOn (1), -# leftTurnSignalOn (2), -# rightTurnSignalOn (3), -# daytimeRunningLightsOn (4), -# reverseLightOn (5), -# fogLightOn (6), -# parkingLightsOn (7) -# } (SIZE(8)) -# ------------------------------------------------------------------------------ +## BIT-STRING ExteriorLights uint8[] value uint8 bits_unused uint8 SIZE_BITS = 8 + uint8 BIT_INDEX_LOW_BEAM_HEADLIGHTS_ON = 0 uint8 BIT_INDEX_HIGH_BEAM_HEADLIGHTS_ON = 1 uint8 BIT_INDEX_LEFT_TURN_SIGNAL_ON = 2 @@ -48,4 +12,3 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg index e6345ff2f..979d501c1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# GenerationDeltaTime ::= INTEGER { oneMilliSec(1) } (0..65535) -# ------------------------------------------------------------------------------ +## INTEGER GenerationDeltaTime uint16 value + uint16 MIN = 0 uint16 MAX = 65535 -uint16 ONE_MILLI_SEC = 1 +uint16 ONE_MILLI_SEC = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg index dcb4d381b..460f5aede 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HardShoulderStatus ::= ENUMERATED {availableForStopping(0), closed(1), availableForDriving(2)} -# ------------------------------------------------------------------------------ +## ENUMERATED HardShoulderStatus uint8 value uint8 AVAILABLE_FOR_STOPPING = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 3bffb4cc1..8257e6ff6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-AnimalOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), wildAnimals(1), herdOfAnimals(2), smallAnimals(3), largeAnimals(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index ca7152557..fd2bb3c4c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -1,40 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-DangerousCurveSubCauseCode ::= INTEGER {unavailable(0), dangerousLeftTurnCurve(1), dangerousRightTurnCurve(2), multipleCurvesStartingWithUnknownTurningDirection(3), multipleCurvesStartingWithLeftTurn(4), multipleCurvesStartingWithRightTurn(5)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationDangerousCurveSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 DANGEROUS_LEFT_TURN_CURVE = 1 uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index 4efb4942d..fa3691914 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-ObstacleOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), shedLoad(1), partsOfVehicles(2), partsOfTyres(3), bigObjects(4), fallenTrees(5), hubCaps(6), waitingVehicles(7)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 SHED_LOAD = 1 uint8 PARTS_OF_VEHICLES = 2 @@ -39,4 +13,3 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index d26c8146b..4e8c792aa 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-SurfaceConditionSubCauseCode ::= INTEGER {unavailable(0), rockfalls(1), earthquakeDamage(2), sewerCollapse(3), subsidence(4), snowDrifts(5), stormDamage(6), burstPipe(7), volcanoEruption(8), fallingIce(9)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationSurfaceConditionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 ROCKFALLS = 1 uint8 EARTHQUAKE_DAMAGE = 2 @@ -41,4 +15,3 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg index 1b545cca4..68df9e493 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Heading ::= SEQUENCE { -# headingValue HeadingValue, -# headingConfidence HeadingConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Heading HeadingValue heading_value + HeadingConfidence heading_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg index 1ee4827f9..4cb626ae0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HeadingConfidence ::= INTEGER {equalOrWithinZeroPointOneDegree (1), equalOrWithinOneDegree (10), outOfRange(126), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER HeadingConfidence uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg index e670dc588..7164cd19b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HeadingValue ::= INTEGER {wgs84North(0), wgs84East(900), wgs84South(1800), wgs84West(2700), unavailable(3601)} (0..3601) -# ------------------------------------------------------------------------------ +## INTEGER HeadingValue uint16 value + uint16 MIN = 0 uint16 MAX = 3601 -uint16 WGS_84_NORTH = 0 -uint16 WGS_84_EAST = 900 -uint16 WGS_84_SOUTH = 1800 -uint16 WGS_84_WEST = 2700 -uint16 UNAVAILABLE = 3601 +uint16 WGS84_NORTH = 0 +uint16 WGS84_EAST = 900 +uint16 WGS84_SOUTH = 1800 +uint16 WGS84_WEST = 2700 +uint16 UNAVAILABLE = 3601 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg index e496a3825..6152a4e51 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HeightLonCarr ::= INTEGER {oneCentimeter(1), unavailable(100)} (1..100) -# ------------------------------------------------------------------------------ +## INTEGER HeightLonCarr uint8 value + uint8 MIN = 1 uint8 MAX = 100 + uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg index d986e3bb6..a6d55d8b0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg @@ -1,42 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HighFrequencyContainer ::= CHOICE { -# basicVehicleContainerHighFrequency BasicVehicleContainerHighFrequency, -# rsuContainerHighFrequency RSUContainerHighFrequency, -# ... -# } -# ------------------------------------------------------------------------------ +## CHOICE HighFrequencyContainer .extensible uint8 choice BasicVehicleContainerHighFrequency basic_vehicle_container_high_frequency -uint8 CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY = 0 - RSUContainerHighFrequency rsu_container_high_frequency + +uint8 CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY = 0 uint8 CHOICE_RSU_CONTAINER_HIGH_FREQUENCY = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index b3d865712..72163a10c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HumanPresenceOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), childrenOnRoadway(1), cyclistOnRoadway(2), motorcyclistOnRoadway(3)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HumanPresenceOnTheRoadSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg index bde36b417..bf40a01d8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HumanProblemSubCauseCode ::= INTEGER {unavailable(0), glycemiaProblem(1), heartProblem(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HumanProblemSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg index cf40d52ab..5af7ec4f4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# InformationQuality ::= INTEGER {unavailable(0), lowest(1), highest(7)} (0..7) -# ------------------------------------------------------------------------------ +## INTEGER InformationQuality uint8 value + uint8 MIN = 0 uint8 MAX = 7 + uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg index c1adc8ce9..15459d1e4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ItineraryPath ::= SEQUENCE SIZE(1..40) OF ReferencePosition -# ------------------------------------------------------------------------------ +## SEQUENCE-OF ItineraryPath ReferencePosition[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 40 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 40 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg index 9957d5f0e..50098612e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg @@ -1,34 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ItsPduHeader ::= SEQUENCE { -# protocolVersion INTEGER (0..255), -# messageID INTEGER{ denm(1), cam(2), poi(3), spatem(4), mapem(5), ivim(6), ev-rsr(7), tistpgtransaction(8), srem(9), ssem(10), evcsn(11), saem(12), rtcmem(13) } (0..255), -- Mantis #7209, #7005 -# ------------------------------------------------------------------------------ +## SEQUENCE ItsPduHeader uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 @@ -53,3 +23,8 @@ uint8 MESSAGE_ID_RTCMEM = 13 StationID station_id + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg index 8ee066832..c2ea265d2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg @@ -1,39 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LanePosition::= INTEGER {offTheRoad(-1), hardShoulder(0), -# outermostDrivingLane(1), secondLaneFromOutside(2)} (-1..14) -# ------------------------------------------------------------------------------ +## INTEGER LanePosition int8 value + int8 MIN = -1 int8 MAX = 14 + int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg index 9ac6f4836..b75736df9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LateralAcceleration ::= SEQUENCE { -# lateralAccelerationValue LateralAccelerationValue, -# lateralAccelerationConfidence AccelerationConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE LateralAcceleration LateralAccelerationValue lateral_acceleration_value + AccelerationConfidence lateral_acceleration_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg index f9b4f8b73..fa022135b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LateralAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredToRight(-1), pointOneMeterPerSecSquaredToLeft(1), unavailable(161)} (-160 .. 161) -# ------------------------------------------------------------------------------ +## INTEGER LateralAccelerationValue int16 value + int16 MIN = -160 int16 MAX = 161 + int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg index 2dc42bbcb..c5be6a7af 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Latitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10), unavailable(900000001)} (-900000000..900000001) -# ------------------------------------------------------------------------------ +## INTEGER Latitude int32 value + int32 MIN = -900000000 int32 MAX = 900000001 + int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg index a9bbe9282..30bb5e2a1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg @@ -1,39 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LightBarSirenInUse ::= BIT STRING { -# lightBarActivated (0), -# sirenActivated (1) -# } (SIZE(2)) -# ------------------------------------------------------------------------------ +## BIT-STRING LightBarSirenInUse uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 + uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg index 8678c6e5a..bddc707df 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Longitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(1800000001)} (-1800000000..1800000001) -# ------------------------------------------------------------------------------ +## INTEGER Longitude int32 value + int32 MIN = -1800000000 int32 MAX = 1800000001 + int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg index 2950f6914..a56e0c176 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LongitudinalAcceleration ::= SEQUENCE { -# longitudinalAccelerationValue LongitudinalAccelerationValue, -# longitudinalAccelerationConfidence AccelerationConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE LongitudinalAcceleration LongitudinalAccelerationValue longitudinal_acceleration_value + AccelerationConfidence longitudinal_acceleration_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg index ae8f739f8..8b438016e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LongitudinalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredForward(1), pointOneMeterPerSecSquaredBackward(-1), unavailable(161)} (-160 .. 161) -# ------------------------------------------------------------------------------ +## INTEGER LongitudinalAccelerationValue int16 value + int16 MIN = -160 int16 MAX = 161 + int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg index 5ddc6a8a3..18e45a1bd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg @@ -1,38 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LowFrequencyContainer ::= CHOICE { -# basicVehicleContainerLowFrequency BasicVehicleContainerLowFrequency, -# ... -# } -# ------------------------------------------------------------------------------ +## CHOICE LowFrequencyContainer .extensible uint8 choice BasicVehicleContainerLowFrequency basic_vehicle_container_low_frequency + uint8 CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY = 0 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg index 4cc239cad..1431e2612 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# NumberOfOccupants ::= INTEGER {oneOccupant (1), unavailable(127)} (0 .. 127) -# ------------------------------------------------------------------------------ +## INTEGER NumberOfOccupants uint8 value + uint8 MIN = 0 uint8 MAX = 127 + uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg index bc47f7c8b..843b5354d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg @@ -1,32 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# OpeningDaysHours ::= UTF8String -# ------------------------------------------------------------------------------ +## Utf8String OpeningDaysHours string value - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg index 04ad62a14..d0ecaba0f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## INTEGER PathDeltaTime -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- +int64 value -# --- ASN.1 Definition --------------------------------------------------------- -# PathDeltaTime ::= INTEGER {tenMilliSecondsInPast(1)} (1..65535, ...) -# ------------------------------------------------------------------------------ - -uint16 value -uint16 MIN = 1 -uint16 MAX = 65535 -uint16 TEN_MILLI_SECONDS_IN_PAST = 1 +int64 MIN = 1 +int64 MAX = 65535 +int64 TEN_MILLI_SECONDS_IN_PAST = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg index f45476300..1b3d17250 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PathHistory::= SEQUENCE (SIZE(0..40)) OF PathPoint -# ------------------------------------------------------------------------------ +## SEQUENCE-OF PathHistory PathPoint[] array -uint8 MIN_SIZE = 0 -uint8 MAX_SIZE = 40 - +uint8 LENGTH_MIN = 0 +uint8 LENGTH_MAX = 40 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg index afe56fd92..a3e508126 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg @@ -1,38 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PathPoint ::= SEQUENCE { -# pathPosition DeltaReferencePosition, -# pathDeltaTime PathDeltaTime OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PathPoint DeltaReferencePosition path_position -PathDeltaTime path_delta_time + bool path_delta_time_is_present +PathDeltaTime path_delta_time + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg index 566e6c9ae..9d69f56cd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PerformanceClass ::= INTEGER {unavailable(0), performanceClassA(1), performanceClassB(2)} (0..7) -# ------------------------------------------------------------------------------ +## INTEGER PerformanceClass uint8 value + uint8 MIN = 0 uint8 MAX = 7 + uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg index 6efe47e5d..2d89e9df9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg @@ -1,34 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PhoneNumber ::= NumericString (SIZE(1..16)) -# ------------------------------------------------------------------------------ +## NumericString PhoneNumber string value -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 16 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg index 18fdd9a5c..cfc9cd9bc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosCentMass ::= INTEGER {tenCentimeters(1), unavailable(63)} (1..63) -# ------------------------------------------------------------------------------ +## INTEGER PosCentMass uint8 value + uint8 MIN = 1 uint8 MAX = 63 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg index 0c72b9a6f..0077d220d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg @@ -1,40 +1,15 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosConfidenceEllipse ::= SEQUENCE { -# semiMajorConfidence SemiAxisLength, -# semiMinorConfidence SemiAxisLength, -# semiMajorOrientation HeadingValue -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PosConfidenceEllipse SemiAxisLength semi_major_confidence + SemiAxisLength semi_minor_confidence + HeadingValue semi_major_orientation + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg index 622ab1d0f..13a451247 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosFrontAx ::= INTEGER {tenCentimeters(1), unavailable(20)} (1..20) -# ------------------------------------------------------------------------------ +## INTEGER PosFrontAx uint8 value + uint8 MIN = 1 uint8 MAX = 20 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg index 5d6168e9f..43154206d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosLonCarr ::= INTEGER {oneCentimeter(1), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER PosLonCarr uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg index 050b310d7..b476f8996 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosPillar ::= INTEGER {tenCentimeters(1), unavailable(30)} (1..30) -# ------------------------------------------------------------------------------ +## INTEGER PosPillar uint8 value + uint8 MIN = 1 uint8 MAX = 30 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg index f11996d64..10c70ae2d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg @@ -1,74 +1,26 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PositionOfOccupants ::= BIT STRING { -# row1LeftOccupied (0), -# row1RightOccupied (1), -# row1MidOccupied (2), -# row1NotDetectable (3), -# row1NotPresent (4), -# row2LeftOccupied (5), -# row2RightOccupied (6), -# row2MidOccupied (7), -# row2NotDetectable (8), -# row2NotPresent (9), -# row3LeftOccupied (10), -# row3RightOccupied (11), -# row3MidOccupied (12), -# row3NotDetectable (13), -# row3NotPresent (14), -# row4LeftOccupied (15), -# row4RightOccupied (16), -# row4MidOccupied (17), -# row4NotDetectable (18), -# row4NotPresent (19)} (SIZE(20)) -# ------------------------------------------------------------------------------ +## BIT-STRING PositionOfOccupants uint8[] value uint8 bits_unused uint8 SIZE_BITS = 20 -uint8 BIT_INDEX_ROW_1_LEFT_OCCUPIED = 0 -uint8 BIT_INDEX_ROW_1_RIGHT_OCCUPIED = 1 -uint8 BIT_INDEX_ROW_1_MID_OCCUPIED = 2 -uint8 BIT_INDEX_ROW_1_NOT_DETECTABLE = 3 -uint8 BIT_INDEX_ROW_1_NOT_PRESENT = 4 -uint8 BIT_INDEX_ROW_2_LEFT_OCCUPIED = 5 -uint8 BIT_INDEX_ROW_2_RIGHT_OCCUPIED = 6 -uint8 BIT_INDEX_ROW_2_MID_OCCUPIED = 7 -uint8 BIT_INDEX_ROW_2_NOT_DETECTABLE = 8 -uint8 BIT_INDEX_ROW_2_NOT_PRESENT = 9 -uint8 BIT_INDEX_ROW_3_LEFT_OCCUPIED = 10 -uint8 BIT_INDEX_ROW_3_RIGHT_OCCUPIED = 11 -uint8 BIT_INDEX_ROW_3_MID_OCCUPIED = 12 -uint8 BIT_INDEX_ROW_3_NOT_DETECTABLE = 13 -uint8 BIT_INDEX_ROW_3_NOT_PRESENT = 14 -uint8 BIT_INDEX_ROW_4_LEFT_OCCUPIED = 15 -uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 -uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 -uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 -uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 +uint8 BIT_INDEX_ROW1_LEFT_OCCUPIED = 0 +uint8 BIT_INDEX_ROW1_RIGHT_OCCUPIED = 1 +uint8 BIT_INDEX_ROW1_MID_OCCUPIED = 2 +uint8 BIT_INDEX_ROW1_NOT_DETECTABLE = 3 +uint8 BIT_INDEX_ROW1_NOT_PRESENT = 4 +uint8 BIT_INDEX_ROW2_LEFT_OCCUPIED = 5 +uint8 BIT_INDEX_ROW2_RIGHT_OCCUPIED = 6 +uint8 BIT_INDEX_ROW2_MID_OCCUPIED = 7 +uint8 BIT_INDEX_ROW2_NOT_DETECTABLE = 8 +uint8 BIT_INDEX_ROW2_NOT_PRESENT = 9 +uint8 BIT_INDEX_ROW3_LEFT_OCCUPIED = 10 +uint8 BIT_INDEX_ROW3_RIGHT_OCCUPIED = 11 +uint8 BIT_INDEX_ROW3_MID_OCCUPIED = 12 +uint8 BIT_INDEX_ROW3_NOT_DETECTABLE = 13 +uint8 BIT_INDEX_ROW3_NOT_PRESENT = 14 +uint8 BIT_INDEX_ROW4_LEFT_OCCUPIED = 15 +uint8 BIT_INDEX_ROW4_RIGHT_OCCUPIED = 16 +uint8 BIT_INDEX_ROW4_MID_OCCUPIED = 17 +uint8 BIT_INDEX_ROW4_NOT_DETECTABLE = 18 +uint8 BIT_INDEX_ROW4_NOT_PRESENT = 19 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg index eea208f31..02b14d0df 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PositionOfPillars ::= SEQUENCE (SIZE(1..3, ...)) OF PosPillar -# ------------------------------------------------------------------------------ +## SEQUENCE-OF PositionOfPillars PosPillar[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 3 - +int64 LENGTH_MIN = 1 +int64 LENGTH_MAX = 3 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg index e0292c4ea..8cfa98a57 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg @@ -1,38 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PositioningSolutionType ::= ENUMERATED {noPositioningSolution(0), sGNSS(1), dGNSS(2), sGNSSplusDR(3), dGNSSplusDR(4), dR(5), ...} -# ------------------------------------------------------------------------------ +## ENUMERATED PositioningSolutionType .extensible uint8 value uint8 NO_POSITIONING_SOLUTION = 0 uint8 S_GNSS = 1 uint8 D_GNSS = 2 -uint8 S_GNSS_PLUS_D_R = 3 -uint8 D_GNSS_PLUS_D_R = 4 +uint8 S_GNS_SPLUS_DR = 3 +uint8 D_GNS_SPLUS_DR = 4 uint8 D_R = 5 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg index bee1a897e..291b9969e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PostCrashSubCauseCode ::= INTEGER {unavailable(0), accidentWithoutECallTriggered (1), accidentWithECallManuallyTriggered (2), accidentWithECallAutomaticallyTriggered (3), accidentWithECallTriggeredWithoutAccessToCellularNetwork(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER PostCrashSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg index 5a6ebbbd4..335f5fcc2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg @@ -1,53 +1,27 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedCommunicationZone ::= SEQUENCE { -# protectedZoneType ProtectedZoneType, -# expiryTime TimestampIts OPTIONAL, -# protectedZoneLatitude Latitude, -# protectedZoneLongitude Longitude, -# protectedZoneRadius ProtectedZoneRadius OPTIONAL, -# protectedZoneID ProtectedZoneID OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ProtectedCommunicationZone .extensible ProtectedZoneType protected_zone_type -TimestampIts expiry_time + bool expiry_time_is_present +TimestampIts expiry_time + Latitude protected_zone_latitude + Longitude protected_zone_longitude -ProtectedZoneRadius protected_zone_radius + bool protected_zone_radius_is_present +ProtectedZoneRadius protected_zone_radius + -ProtectedZoneID protected_zone_id bool protected_zone_id_is_present +ProtectedZoneID protected_zone_id + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg index cc6d8ea62..3e68a4b85 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedCommunicationZonesRSU ::= SEQUENCE (SIZE(1..16)) OF ProtectedCommunicationZone -# ------------------------------------------------------------------------------ +## SEQUENCE-OF ProtectedCommunicationZonesRSU ProtectedCommunicationZone[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 16 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 16 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg index 6a0344d74..8ad38e935 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedZoneID ::= INTEGER (0.. 134217727) -# ------------------------------------------------------------------------------ +## INTEGER ProtectedZoneID uint32 value + uint32 MIN = 0 uint32 MAX = 134217727 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg index 7f1a3f2c2..e5fce0ff6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## INTEGER ProtectedZoneRadius -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- +int64 value -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedZoneRadius ::= INTEGER {oneMeter(1)} (1..255,...) -# ------------------------------------------------------------------------------ - -uint8 value -uint8 MIN = 1 -uint8 MAX = 255 -uint8 ONE_METER = 1 +int64 MIN = 1 +int64 MAX = 255 +int64 ONE_METER = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg index 3283db4e0..277c99b9a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedZoneType::= ENUMERATED { permanentCenDsrcTolling (0), ..., temporaryCenDsrcTolling (1) } -# ------------------------------------------------------------------------------ +## ENUMERATED ProtectedZoneType .extensible uint8 value uint8 PERMANENT_CEN_DSRC_TOLLING = 0 +# .extended uint8 TEMPORARY_CEN_DSRC_TOLLING = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg index f70514140..b067e6f81 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PtActivation ::= SEQUENCE { -# ptActivationType PtActivationType, -# ptActivationData PtActivationData -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PtActivation PtActivationType pt_activation_type + PtActivationData pt_activation_data + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg index 0fb3a6413..9e0108cdf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg @@ -1,34 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PtActivationData ::= OCTET STRING (SIZE(1..20)) -# ------------------------------------------------------------------------------ +## OCTET-STRING PtActivationData uint8[] value -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 20 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg index 0d373552c..dbf87a49d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PtActivationType ::= INTEGER {undefinedCodingType(0), r09-16CodingType(1), vdv-50149CodingType(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER PtActivationType uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNDEFINED_CODING_TYPE = 0 -uint8 R_09_16_CODING_TYPE = 1 +uint8 R09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg index c6f767b3c..93fd6639a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg @@ -1,38 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PublicTransportContainer ::= SEQUENCE { -# embarkationStatus EmbarkationStatus, -# ptActivation PtActivation OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PublicTransportContainer EmbarkationStatus embarkation_status -PtActivation pt_activation + bool pt_activation_is_present +PtActivation pt_activation + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg index c75e9fee3..62fc3d858 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## SEQUENCE RSUContainerHighFrequency .extensible + +bool protected_communication_zones_rsu_is_present +ProtectedCommunicationZonesRSU protected_communication_zones_rsu + + -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -# --- ASN.1 Definition --------------------------------------------------------- -# RSUContainerHighFrequency ::= SEQUENCE { -# protectedCommunicationZonesRSU ProtectedCommunicationZonesRSU OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ -ProtectedCommunicationZonesRSU protected_communication_zones_rsu -bool protected_communication_zones_rsu_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg index ff37f4ebf..2e15eb7bd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg @@ -1,43 +1,18 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ReferencePosition ::= SEQUENCE { -# latitude Latitude, -# longitude Longitude, -# positionConfidenceEllipse PosConfidenceEllipse , -# altitude Altitude -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ReferencePosition Latitude latitude + Longitude longitude + PosConfidenceEllipse position_confidence_ellipse + Altitude altitude + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg index 03f962736..52210df13 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg @@ -1,40 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RelevanceDistance ::= ENUMERATED {lessThan50m(0), lessThan100m(1), lessThan200m(2), lessThan500m(3), lessThan1000m(4), lessThan5km(5), lessThan10km(6), over10km(7)} -# ------------------------------------------------------------------------------ +## ENUMERATED RelevanceDistance uint8 value -uint8 LESS_THAN_50M = 0 -uint8 LESS_THAN_100M = 1 -uint8 LESS_THAN_200M = 2 -uint8 LESS_THAN_500M = 3 -uint8 LESS_THAN_1000M = 4 -uint8 LESS_THAN_5KM = 5 -uint8 LESS_THAN_10KM = 6 -uint8 OVER_10KM = 7 +uint8 LESS_THAN50M = 0 +uint8 LESS_THAN100M = 1 +uint8 LESS_THAN200M = 2 +uint8 LESS_THAN500M = 3 +uint8 LESS_THAN1000M = 4 +uint8 LESS_THAN5KM = 5 +uint8 LESS_THAN10KM = 6 +uint8 OVER10KM = 7 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg index 6a2060b60..1b942c3ed 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RelevanceTrafficDirection ::= ENUMERATED {allTrafficDirections(0), upstreamTraffic(1), downstreamTraffic(2), oppositeTraffic(3)} -# ------------------------------------------------------------------------------ +## ENUMERATED RelevanceTrafficDirection uint8 value uint8 ALL_TRAFFIC_DIRECTIONS = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg index e87b70032..45e45c756 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RequestResponseIndication ::= ENUMERATED {request(0), response(1)} -# ------------------------------------------------------------------------------ +## ENUMERATED RequestResponseIndication uint8 value uint8 REQUEST = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index 3cd20fa4f..bacf1a7ea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -1,40 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RescueAndRecoveryWorkInProgressSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicles(1), rescueHelicopterLanding(2), policeActivityOngoing(3), medicalEmergencyOngoing(4), childAbductionInProgress(5)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLES = 1 uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg index 197d53528..544ac9987 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg @@ -1,34 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## SEQUENCE RescueContainer + +LightBarSirenInUse light_bar_siren_in_use + + -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -# --- ASN.1 Definition --------------------------------------------------------- -# RescueContainer ::= SEQUENCE { -# lightBarSirenInUse LightBarSirenInUse -# } -# ------------------------------------------------------------------------------ -LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg index d5103c64e..61e48f1e6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RestrictedTypes ::= SEQUENCE (SIZE(1..3, ...)) OF StationType -# ------------------------------------------------------------------------------ +## SEQUENCE-OF RestrictedTypes StationType[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 3 - +int64 LENGTH_MIN = 1 +int64 LENGTH_MAX = 3 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg index e2615acec..dd2e542e7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg @@ -1,36 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RoadType ::= ENUMERATED { -# urban-NoStructuralSeparationToOppositeLanes(0), -# urban-WithStructuralSeparationToOppositeLanes(1), -# nonUrban-NoStructuralSeparationToOppositeLanes(2), -# nonUrban-WithStructuralSeparationToOppositeLanes(3)} -# ------------------------------------------------------------------------------ +## ENUMERATED RoadType uint8 value uint8 URBAN_NO_STRUCTURAL_SEPARATION_TO_OPPOSITE_LANES = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg index cc3058338..fbd474704 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg @@ -1,42 +1,17 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RoadWorksContainerBasic ::= SEQUENCE { -# roadworksSubCauseCode RoadworksSubCauseCode OPTIONAL, -# lightBarSirenInUse LightBarSirenInUse, -# closedLanes ClosedLanes OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE RoadWorksContainerBasic -RoadworksSubCauseCode roadworks_sub_cause_code bool roadworks_sub_cause_code_is_present +RoadworksSubCauseCode roadworks_sub_cause_code + LightBarSirenInUse light_bar_siren_in_use -ClosedLanes closed_lanes + bool closed_lanes_is_present +ClosedLanes closed_lanes + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg index 153e11c4e..20057cc6a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RoadworksSubCauseCode ::= INTEGER {unavailable(0), majorRoadworks(1), roadMarkingWork(2), slowMovingRoadMaintenance(3), shortTermStationaryRoadworks(4), streetCleaning(5), winterService(6)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER RoadworksSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 MAJOR_ROADWORKS = 1 uint8 ROAD_MARKING_WORK = 2 @@ -38,4 +12,3 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg index cc44061fb..bc38f220d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg @@ -1,46 +1,21 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SafetyCarContainer ::= SEQUENCE { -# lightBarSirenInUse LightBarSirenInUse, -# incidentIndication CauseCode OPTIONAL, -# trafficRule TrafficRule OPTIONAL, -# speedLimit SpeedLimit OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE SafetyCarContainer LightBarSirenInUse light_bar_siren_in_use -CauseCode incident_indication + bool incident_indication_is_present +CauseCode incident_indication + -TrafficRule traffic_rule bool traffic_rule_is_present +TrafficRule traffic_rule + -SpeedLimit speed_limit bool speed_limit_is_present +SpeedLimit speed_limit + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg index 976c006d8..083e860ab 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SemiAxisLength ::= INTEGER{oneCentimeter(1), outOfRange(4094), unavailable(4095)} (0..4095) -# ------------------------------------------------------------------------------ +## INTEGER SemiAxisLength uint16 value + uint16 MIN = 0 uint16 MAX = 4095 + uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg index 3ee9128cd..5171880d2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SequenceNumber ::= INTEGER (0..65535) -# ------------------------------------------------------------------------------ +## INTEGER SequenceNumber uint16 value + uint16 MIN = 0 uint16 MAX = 65535 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg index 580af19c9..a7d121127 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SignalViolationSubCauseCode ::= INTEGER {unavailable(0), stopSignViolation(1), trafficLightViolation(2), turningRegulationViolation(3)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER SignalViolationSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg index d7c7e96b7..131897657 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SlowVehicleSubCauseCode ::= INTEGER {unavailable(0), maintenanceVehicle(1), vehiclesSlowingToLookAtAccident(2), abnormalLoad(3), abnormalWideLoad(4), convoy(5), snowplough(6), deicing(7), saltingVehicles(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER SlowVehicleSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 MAINTENANCE_VEHICLE = 1 uint8 VEHICLES_SLOWING_TO_LOOK_AT_ACCIDENT = 2 @@ -40,4 +14,3 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg index 15becf54c..50b0ac923 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpecialTransportContainer ::= SEQUENCE { -# specialTransportType SpecialTransportType, -# lightBarSirenInUse LightBarSirenInUse -# } -# ------------------------------------------------------------------------------ +## SEQUENCE SpecialTransportContainer SpecialTransportType special_transport_type + LightBarSirenInUse light_bar_siren_in_use + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg index 8f5fcd9d6..ca8a3f72a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg @@ -1,38 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpecialTransportType ::= BIT STRING {heavyLoad(0), excessWidth(1), excessLength(2), excessHeight(3)} (SIZE(4)) -# ------------------------------------------------------------------------------ +## BIT-STRING SpecialTransportType uint8[] value uint8 bits_unused uint8 SIZE_BITS = 4 + uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg index 2235487fe..38c8797bc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg @@ -1,62 +1,21 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpecialVehicleContainer ::= CHOICE { -# publicTransportContainer PublicTransportContainer, -# specialTransportContainer SpecialTransportContainer, -# dangerousGoodsContainer DangerousGoodsContainer, -# roadWorksContainerBasic RoadWorksContainerBasic, -# rescueContainer RescueContainer, -# emergencyContainer EmergencyContainer, -# safetyCarContainer SafetyCarContainer, -# ... -# } -# ------------------------------------------------------------------------------ +## CHOICE SpecialVehicleContainer .extensible uint8 choice PublicTransportContainer public_transport_container -uint8 CHOICE_PUBLIC_TRANSPORT_CONTAINER = 0 - SpecialTransportContainer special_transport_container -uint8 CHOICE_SPECIAL_TRANSPORT_CONTAINER = 1 - DangerousGoodsContainer dangerous_goods_container -uint8 CHOICE_DANGEROUS_GOODS_CONTAINER = 2 - RoadWorksContainerBasic road_works_container_basic -uint8 CHOICE_ROAD_WORKS_CONTAINER_BASIC = 3 - RescueContainer rescue_container -uint8 CHOICE_RESCUE_CONTAINER = 4 - EmergencyContainer emergency_container -uint8 CHOICE_EMERGENCY_CONTAINER = 5 - SafetyCarContainer safety_car_container + +uint8 CHOICE_PUBLIC_TRANSPORT_CONTAINER = 0 +uint8 CHOICE_SPECIAL_TRANSPORT_CONTAINER = 1 +uint8 CHOICE_DANGEROUS_GOODS_CONTAINER = 2 +uint8 CHOICE_ROAD_WORKS_CONTAINER_BASIC = 3 +uint8 CHOICE_RESCUE_CONTAINER = 4 +uint8 CHOICE_EMERGENCY_CONTAINER = 5 uint8 CHOICE_SAFETY_CAR_CONTAINER = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg index ecfc591e4..cac581f03 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Speed ::= SEQUENCE { -# speedValue SpeedValue, -# speedConfidence SpeedConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Speed SpeedValue speed_value + SpeedConfidence speed_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg index 487873b36..34a84c0fc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpeedConfidence ::= INTEGER {equalOrWithinOneCentimeterPerSec(1), equalOrWithinOneMeterPerSec(100), outOfRange(126), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER SpeedConfidence uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg index 4cf1a9d03..3a459e7ce 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpeedLimit ::= INTEGER {oneKmPerHour(1)} (1..255) -# ------------------------------------------------------------------------------ +## INTEGER SpeedLimit uint8 value + uint8 MIN = 1 uint8 MAX = 255 -uint8 ONE_KM_PER_HOUR = 1 +uint8 ONE_KM_PER_HOUR = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg index b3d89beff..e18097a0f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpeedValue ::= INTEGER {standstill(0), oneCentimeterPerSec(1), unavailable(16383)} (0..16383) -# ------------------------------------------------------------------------------ +## INTEGER SpeedValue uint16 value + uint16 MIN = 0 uint16 MAX = 16383 + uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg index 9d36a5a65..f49d34323 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationID ::= INTEGER(0..4294967295) -# ------------------------------------------------------------------------------ +## INTEGER StationID uint32 value + uint32 MIN = 0 uint32 MAX = 4294967295 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg index 104c6821e..e91775578 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationType ::= INTEGER {unknown(0), pedestrian(1), cyclist(2), moped(3), motorcycle(4), passengerCar(5), bus(6), -# lightTruck(7), heavyTruck(8), trailer(9), specialVehicles(10), tram(11), roadSideUnit(15)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER StationType uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNKNOWN = 0 uint8 PEDESTRIAN = 1 uint8 CYCLIST = 2 @@ -45,4 +18,3 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg index e0133c7a8..80b7c9660 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg @@ -1,36 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationarySince ::= ENUMERATED {lessThan1Minute(0), lessThan2Minutes(1), lessThan15Minutes(2), equalOrGreater15Minutes(3)} -# ------------------------------------------------------------------------------ +## ENUMERATED StationarySince uint8 value -uint8 LESS_THAN_1_MINUTE = 0 -uint8 LESS_THAN_2_MINUTES = 1 -uint8 LESS_THAN_15_MINUTES = 2 -uint8 EQUAL_OR_GREATER_15_MINUTES = 3 +uint8 LESS_THAN1_MINUTE = 0 +uint8 LESS_THAN2_MINUTES = 1 +uint8 LESS_THAN15_MINUTES = 2 +uint8 EQUAL_OR_GREATER15_MINUTES = 3 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg index 190a7c78e..c48785887 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -1,40 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationaryVehicleSubCauseCode ::= INTEGER {unavailable(0), humanProblem(1), vehicleBreakdown(2), postCrash(3), publicTransportStop(4), carryingDangerousGoods(5)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER StationaryVehicleSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 HUMAN_PROBLEM = 1 uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg index 918cc7a8d..76e9ef597 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SteeringWheelAngle ::= SEQUENCE { -# steeringWheelAngleValue SteeringWheelAngleValue, -# steeringWheelAngleConfidence SteeringWheelAngleConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE SteeringWheelAngle SteeringWheelAngleValue steering_wheel_angle_value + SteeringWheelAngleConfidence steering_wheel_angle_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg index bf209a62e..dbd12e458 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SteeringWheelAngleConfidence ::= INTEGER {equalOrWithinOnePointFiveDegree (1), outOfRange(126), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER SteeringWheelAngleConfidence uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg index fbda5ff63..9b04cdf9f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SteeringWheelAngleValue ::= INTEGER {straight(0), onePointFiveDegreesToRight(-1), onePointFiveDegreesToLeft(1), unavailable(512)} (-511..512) -# ------------------------------------------------------------------------------ +## INTEGER SteeringWheelAngleValue int16 value + int16 MIN = -511 int16 MAX = 512 + int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg index 5f328fa69..b08a83005 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SubCauseCodeType ::= INTEGER (0..255) -# ------------------------------------------------------------------------------ +## INTEGER SubCauseCodeType uint8 value + uint8 MIN = 0 uint8 MAX = 255 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg index 2e351568e..f2a497ef5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Temperature ::= INTEGER {equalOrSmallerThanMinus60Deg (-60), oneDegreeCelsius(1), equalOrGreaterThan67Deg(67)} (-60..67) -# ------------------------------------------------------------------------------ +## INTEGER Temperature int8 value + int8 MIN = -60 int8 MAX = 67 -int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 -int8 ONE_DEGREE_CELSIUS = 1 -int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 +int8 EQUAL_OR_SMALLER_THAN_MINUS60_DEG = -60 +int8 ONE_DEGREE_CELSIUS = 1 +int8 EQUAL_OR_GREATER_THAN67_DEG = 67 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg index 6871563ba..342fcf26b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TimestampIts ::= INTEGER {utcStartOf2004(0), oneMillisecAfterUTCStartOf2004(1)} (0..4398046511103) -# ------------------------------------------------------------------------------ +## INTEGER TimestampIts uint64 value + uint64 MIN = 0 uint64 MAX = 4398046511103 -uint64 UTC_START_OF_2004 = 0 -uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 +uint64 UTC_START_OF2004 = 0 +uint64 ONE_MILLISEC_AFTER_UTC_START_OF2004 = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg index db7a2bb0f..479157e9d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Traces ::= SEQUENCE SIZE(1..7) OF PathHistory -# ------------------------------------------------------------------------------ +## SEQUENCE-OF Traces PathHistory[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 7 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 7 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg index 38061b4a4..c060c7ebc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TrafficConditionSubCauseCode ::= INTEGER {unavailable(0), increasedVolumeOfTraffic(1), trafficJamSlowlyIncreasing(2), trafficJamIncreasing(3), trafficJamStronglyIncreasing(4), trafficStationary(5), trafficJamSlightlyDecreasing(6), trafficJamDecreasing(7), trafficJamStronglyDecreasing(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER TrafficConditionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 INCREASED_VOLUME_OF_TRAFFIC = 1 uint8 TRAFFIC_JAM_SLOWLY_INCREASING = 2 @@ -40,4 +14,3 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg index cc8afc852..e138ac055 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg @@ -1,33 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TrafficRule ::= ENUMERATED {noPassing(0), noPassingForTrucks(1), passToRight(2), passToLeft(3), ... -# } -# ------------------------------------------------------------------------------ +## ENUMERATED TrafficRule .extensible uint8 value uint8 NO_PASSING = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg index 343d094dd..e505df9b5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TransmissionInterval ::= INTEGER {oneMilliSecond(1), tenSeconds(10000)} (1..10000) -# ------------------------------------------------------------------------------ +## INTEGER TransmissionInterval uint16 value + uint16 MIN = 1 uint16 MAX = 10000 + uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg index 99ccaa91d..11de9132c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TurningRadius ::= INTEGER {point4Meters(1), unavailable(255)} (1..255) -# ------------------------------------------------------------------------------ +## INTEGER TurningRadius uint8 value + uint8 MIN = 1 uint8 MAX = 255 -uint8 POINT_4_METERS = 1 -uint8 UNAVAILABLE = 255 +uint8 POINT4_METERS = 1 +uint8 UNAVAILABLE = 255 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg index e9beb0f3f..b08a5c238 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg @@ -1,33 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VDS ::= IA5String (SIZE(6)) -# ------------------------------------------------------------------------------ +## Ia5String VDS string value -uint8 SIZE = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg index 3cfc6ffe7..d11827ef1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ValidityDuration ::= INTEGER {timeOfDetection(0), oneSecondAfterDetection(1)} (0..86400) -# ------------------------------------------------------------------------------ +## INTEGER ValidityDuration uint32 value + uint32 MIN = 0 uint32 MAX = 86400 + uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg index 40c794fa4..ef3d2d1c6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleBreakdownSubCauseCode ::= INTEGER {unavailable(0), lackOfFuel (1), lackOfBatteryPower (2), engineProblem(3), transmissionProblem(4), engineCoolingProblem(5), brakingSystemProblem(6), steeringProblem(7), tyrePuncture(8), tyrePressureProblem(9)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER VehicleBreakdownSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 LACK_OF_FUEL = 1 uint8 LACK_OF_BATTERY_POWER = 2 @@ -41,4 +15,3 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg index 411ade20f..1b7b25c07 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg @@ -1,40 +1,14 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleIdentification ::= SEQUENCE { -# wMInumber WMInumber OPTIONAL, -# vDS VDS OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ - -WMInumber wm_inumber -bool wm_inumber_is_present - -VDS vds -bool vds_is_present +## SEQUENCE VehicleIdentification .extensible + +bool w_m_inumber_is_present +WMInumber w_m_inumber + + +bool v_ds_is_present +VDS v_ds + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg index 0657adbdc..543253116 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleLength ::= SEQUENCE { -# vehicleLengthValue VehicleLengthValue, -# vehicleLengthConfidenceIndication VehicleLengthConfidenceIndication -# } -# ------------------------------------------------------------------------------ +## SEQUENCE VehicleLength VehicleLengthValue vehicle_length_value + VehicleLengthConfidenceIndication vehicle_length_confidence_indication + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg index b5a008bba..5cd4611f7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleLengthConfidenceIndication ::= ENUMERATED {noTrailerPresent(0), trailerPresentWithKnownLength(1), trailerPresentWithUnknownLength(2), trailerPresenceIsUnknown(3), unavailable(4)} -# ------------------------------------------------------------------------------ +## ENUMERATED VehicleLengthConfidenceIndication uint8 value uint8 NO_TRAILER_PRESENT = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg index e253cfda3..2c2bc6e87 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleLengthValue ::= INTEGER {tenCentimeters(1), outOfRange(1022), unavailable(1023)} (1..1023) -# ------------------------------------------------------------------------------ +## INTEGER VehicleLengthValue uint16 value + uint16 MIN = 1 uint16 MAX = 1023 + uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg index d74f09b5c..949dc93b2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleMass ::= INTEGER {hundredKg(1), unavailable(1024)} (1..1024) -# ------------------------------------------------------------------------------ +## INTEGER VehicleMass uint16 value + uint16 MIN = 1 uint16 MAX = 1024 + uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg index daeb43921..dee2e6e66 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleRole ::= ENUMERATED {default(0), publicTransport(1), specialTransport(2), dangerousGoods(3), roadWork(4), rescue(5), emergency(6), safetyCar(7), agriculture(8), commercial(9), military(10), roadOperator(11), taxi(12), reserved1(13), reserved2(14), reserved3(15)} -# ------------------------------------------------------------------------------ +## ENUMERATED VehicleRole uint8 value uint8 DEFAULT = 0 @@ -42,7 +14,7 @@ uint8 COMMERCIAL = 9 uint8 MILITARY = 10 uint8 ROAD_OPERATOR = 11 uint8 TAXI = 12 -uint8 RESERVED_1 = 13 -uint8 RESERVED_2 = 14 -uint8 RESERVED_3 = 15 +uint8 RESERVED1 = 13 +uint8 RESERVED2 = 14 +uint8 RESERVED3 = 15 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg index c209c3b57..0ff4d5cee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleWidth ::= INTEGER {tenCentimeters(1), outOfRange(61), unavailable(62)} (1..62) -# ------------------------------------------------------------------------------ +## INTEGER VehicleWidth uint8 value + uint8 MIN = 1 uint8 MAX = 62 + uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg index 3da431c59..c6927a06c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VerticalAcceleration ::= SEQUENCE { -# verticalAccelerationValue VerticalAccelerationValue, -# verticalAccelerationConfidence AccelerationConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE VerticalAcceleration VerticalAccelerationValue vertical_acceleration_value + AccelerationConfidence vertical_acceleration_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg index 4f208993e..2267e732c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VerticalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredUp(1), pointOneMeterPerSecSquaredDown(-1), unavailable(161)} (-160 .. 161) -# ------------------------------------------------------------------------------ +## INTEGER VerticalAccelerationValue int16 value + int16 MIN = -160 int16 MAX = 161 + int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg index 34b682f9a..fef01bdbf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg @@ -1,34 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# WMInumber ::= IA5String (SIZE(1..3)) -# ------------------------------------------------------------------------------ +## Ia5String WMInumber string value -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg index af24dccaf..4a9feb773 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# WheelBaseVehicle ::= INTEGER {tenCentimeters(1), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER WheelBaseVehicle uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg index 0f8080f05..4ee06efd1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# WrongWayDrivingSubCauseCode ::= INTEGER {unavailable(0), wrongLane(1), wrongDirection(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER WrongWayDrivingSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg index 2284e9ba8..69e8f08eb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# YawRate::= SEQUENCE { -# yawRateValue YawRateValue, -# yawRateConfidence YawRateConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE YawRate YawRateValue yaw_rate_value + YawRateConfidence yaw_rate_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg index 4150e4776..72f3c0bf8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg @@ -1,42 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# YawRateConfidence ::= ENUMERATED { -# degSec-000-01 (0), -# degSec-000-05 (1), -# degSec-000-10 (2), -# degSec-001-00 (3), -# degSec-005-00 (4), -# degSec-010-00 (5), -# degSec-100-00 (6), -# outOfRange (7), -# unavailable (8) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED YawRateConfidence uint8 value uint8 DEG_SEC_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg index 9564c6bee..8c0e228b7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# YawRateValue ::= INTEGER {straight(0), degSec-000-01ToRight(-1), degSec-000-01ToLeft(1), unavailable(32767)} (-32766..32767) -# ------------------------------------------------------------------------------ +## INTEGER YawRateValue int16 value + int16 MIN = -32766 int16 MAX = 32767 + int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg index 4a4e59cb3..9865b14b3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AccelerationConfidence ::= INTEGER {pointOneMeterPerSecSquared(1), outOfRange(101), unavailable(102)} (0 .. 102) -# ------------------------------------------------------------------------------ +## INTEGER AccelerationConfidence uint8 value + uint8 MIN = 0 uint8 MAX = 102 + uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg index e1729d637..4a7f9d5c5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg @@ -1,44 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AccelerationControl ::= BIT STRING { -# brakePedalEngaged (0), -# gasPedalEngaged (1), -# emergencyBrakeEngaged (2), -# collisionWarningEngaged (3), -# accEngaged (4), -# cruiseControlEngaged (5), -# speedLimiterEngaged (6) -# } (SIZE(7)) -# ------------------------------------------------------------------------------ +## BIT-STRING AccelerationControl uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 + uint8 BIT_INDEX_BRAKE_PEDAL_ENGAGED = 0 uint8 BIT_INDEX_GAS_PEDAL_ENGAGED = 1 uint8 BIT_INDEX_EMERGENCY_BRAKE_ENGAGED = 2 @@ -46,4 +11,3 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg index b09fec1ee..796d1b8b9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AccidentSubCauseCode ::= INTEGER {unavailable(0), multiVehicleAccident(1), heavyAccident(2), accidentInvolvingLorry(3), accidentInvolvingBus(4), accidentInvolvingHazardousMaterials(5), accidentOnOppositeLane(6), unsecuredAccident(7), assistanceRequested(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AccidentSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 MULTI_VEHICLE_ACCIDENT = 1 uint8 HEAVY_ACCIDENT = 2 @@ -40,4 +14,3 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg index 845afc0d2..20cb30ac9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ActionID ::= SEQUENCE { -# originatingStationID StationID, -# sequenceNumber SequenceNumber -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ActionID StationID originating_station_id + SequenceNumber sequence_number + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 54039db9b..8dfc404d6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-AdhesionSubCauseCode ::= INTEGER {unavailable(0), heavyFrostOnRoad(1), fuelOnRoad(2), mudOnRoad(3), snowOnRoad(4), iceOnRoad(5), blackIceOnRoad(6), oilOnRoad(7), looseChippings(8), instantBlackIce(9), roadsSalted(10)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionAdhesionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 HEAVY_FROST_ON_ROAD = 1 uint8 FUEL_ON_ROAD = 2 @@ -42,4 +16,3 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 0e9e5babd..5e8c226b8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-ExtremeWeatherConditionSubCauseCode ::= INTEGER {unavailable(0), strongWinds(1), damagingHail(2), hurricane(3), thunderstorm(4), tornado(5), blizzard(6)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 STRONG_WINDS = 1 uint8 DAMAGING_HAIL = 2 @@ -38,4 +12,3 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index 643edd4b2..b71e00a5b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-PrecipitationSubCauseCode ::= INTEGER {unavailable(0), heavyRain(1), heavySnowfall(2), softHail(3)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index cecf863ab..2914f7b84 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AdverseWeatherCondition-VisibilitySubCauseCode ::= INTEGER {unavailable(0), fog(1), smoke(2), heavySnowfall(3), heavyRain(4), heavyHail(5), lowSunGlare(6), sandstorms(7), swarmsOfInsects(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER AdverseWeatherConditionVisibilitySubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 FOG = 1 uint8 SMOKE = 2 @@ -40,4 +14,3 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg index 72f86507e..7ad3eb900 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg @@ -1,56 +1,30 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AlacarteContainer ::= SEQUENCE { -# lanePosition LanePosition OPTIONAL, -# impactReduction ImpactReductionContainer OPTIONAL, -# externalTemperature Temperature OPTIONAL, -# roadWorks RoadWorksContainerExtended OPTIONAL, -# positioningSolution PositioningSolutionType OPTIONAL, -# stationaryVehicle StationaryVehicleContainer OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE AlacarteContainer .extensible -LanePosition lane_position bool lane_position_is_present +LanePosition lane_position + -ImpactReductionContainer impact_reduction bool impact_reduction_is_present +ImpactReductionContainer impact_reduction + -Temperature external_temperature bool external_temperature_is_present +Temperature external_temperature + -RoadWorksContainerExtended road_works bool road_works_is_present +RoadWorksContainerExtended road_works + -PositioningSolutionType positioning_solution bool positioning_solution_is_present +PositioningSolutionType positioning_solution + -StationaryVehicleContainer stationary_vehicle bool stationary_vehicle_is_present +StationaryVehicleContainer stationary_vehicle + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg index 1e84f8bc4..ee0b01eb4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Altitude ::= SEQUENCE { -# altitudeValue AltitudeValue, -# altitudeConfidence AltitudeConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Altitude AltitudeValue altitude_value + AltitudeConfidence altitude_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg index 31c124195..e6081a967 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg @@ -1,49 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AltitudeConfidence ::= ENUMERATED { -# alt-000-01 (0), -# alt-000-02 (1), -# alt-000-05 (2), -# alt-000-10 (3), -# alt-000-20 (4), -# alt-000-50 (5), -# alt-001-00 (6), -# alt-002-00 (7), -# alt-005-00 (8), -# alt-010-00 (9), -# alt-020-00 (10), -# alt-050-00 (11), -# alt-100-00 (12), -# alt-200-00 (13), -# outOfRange (14), -# unavailable (15) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED AltitudeConfidence uint8 value uint8 ALT_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg index 404256f66..db7c77a3d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# AltitudeValue ::= INTEGER {referenceEllipsoidSurface(0), oneCentimeter(1), unavailable(800001)} (-100000..800001) -# ------------------------------------------------------------------------------ +## INTEGER AltitudeValue int32 value + int32 MIN = -100000 int32 MAX = 800001 + int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg index 13f0048db..e3fdccaff 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg @@ -1,38 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CauseCode ::= SEQUENCE { -# causeCode CauseCodeType, -# subCauseCode SubCauseCodeType, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CauseCode .extensible CauseCodeType cause_code + SubCauseCodeType sub_cause_code + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg index 1a2cc7175..172a0fc12 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg @@ -1,64 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CauseCodeType ::= INTEGER { -# reserved (0), -# trafficCondition (1), -# accident (2), -# roadworks (3), -# impassability (5), -# adverseWeatherCondition-Adhesion (6), -# aquaplannning (7), -# hazardousLocation-SurfaceCondition (9), -# hazardousLocation-ObstacleOnTheRoad (10), -# hazardousLocation-AnimalOnTheRoad (11), -# humanPresenceOnTheRoad (12), -# wrongWayDriving (14), -# rescueAndRecoveryWorkInProgress (15), -# adverseWeatherCondition-ExtremeWeatherCondition (17), -# adverseWeatherCondition-Visibility (18), -# adverseWeatherCondition-Precipitation (19), -# slowVehicle (26), -# dangerousEndOfQueue (27), -# vehicleBreakdown (91), -# postCrash (92), -# humanProblem (93), -# stationaryVehicle (94), -# emergencyVehicleApproaching (95), -# hazardousLocation-DangerousCurve (96), -# collisionRisk (97), -# signalViolation (98), -# dangerousSituation (99) -# } (0..255) -# ------------------------------------------------------------------------------ +## INTEGER CauseCodeType uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 RESERVED = 0 uint8 TRAFFIC_CONDITION = 1 uint8 ACCIDENT = 2 @@ -86,4 +32,3 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg index 39c0affef..449a28242 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg @@ -1,42 +1,16 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CenDsrcTollingZone ::= SEQUENCE { -# protectedZoneLatitude Latitude, -# protectedZoneLongitude Longitude, -# cenDsrcTollingZoneID CenDsrcTollingZoneID OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE CenDsrcTollingZone .extensible Latitude protected_zone_latitude + Longitude protected_zone_longitude -CenDsrcTollingZoneID cen_dsrc_tolling_zone_id + bool cen_dsrc_tolling_zone_id_is_present +CenDsrcTollingZoneID cen_dsrc_tolling_zone_id + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg index 50b563c91..efb20a09e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg @@ -1,32 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CenDsrcTollingZoneID ::= ProtectedZoneID -# ------------------------------------------------------------------------------ +## TYPE-ALIAS CenDsrcTollingZoneID ProtectedZoneID value - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg index 4f4b22816..aec88d388 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg @@ -1,44 +1,18 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ClosedLanes ::= SEQUENCE { -# innerhardShoulderStatus HardShoulderStatus OPTIONAL, -# outerhardShoulderStatus HardShoulderStatus OPTIONAL, -# drivingLaneStatus DrivingLaneStatus OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ClosedLanes .extensible -HardShoulderStatus innerhard_shoulder_status bool innerhard_shoulder_status_is_present +HardShoulderStatus innerhard_shoulder_status + -HardShoulderStatus outerhard_shoulder_status bool outerhard_shoulder_status_is_present +HardShoulderStatus outerhard_shoulder_status + -DrivingLaneStatus driving_lane_status bool driving_lane_status_is_present +DrivingLaneStatus driving_lane_status + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg index cbd4d715a..f3afe70d0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CollisionRiskSubCauseCode ::= INTEGER {unavailable(0), longitudinalCollisionRisk(1), crossingCollisionRisk(2), lateralCollisionRisk(3), vulnerableRoadUser(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER CollisionRiskSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg index ac99ea8a4..21f001b6a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Curvature ::= SEQUENCE { -# curvatureValue CurvatureValue, -# curvatureConfidence CurvatureConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Curvature CurvatureValue curvature_value + CurvatureConfidence curvature_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg index 65473f0cb..d76cf7cdd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CurvatureCalculationMode ::= ENUMERATED {yawRateUsed(0), yawRateNotUsed(1), unavailable(2), ...} -# ------------------------------------------------------------------------------ +## ENUMERATED CurvatureCalculationMode .extensible uint8 value uint8 YAW_RATE_USED = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg index 56dea214e..17bbbf4de 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg @@ -1,41 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CurvatureConfidence ::= ENUMERATED { -# onePerMeter-0-00002 (0), -# onePerMeter-0-0001 (1), -# onePerMeter-0-0005 (2), -# onePerMeter-0-002 (3), -# onePerMeter-0-01 (4), -# onePerMeter-0-1 (5), -# outOfRange (6), -# unavailable (7) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED CurvatureConfidence uint8 value uint8 ONE_PER_METER_0_00002 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg index f3ce6a111..da3928552 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# CurvatureValue ::= INTEGER {straight(0), unavailable(1023)} (-1023..1023) -# ------------------------------------------------------------------------------ +## INTEGER CurvatureValue int16 value + int16 MIN = -1023 int16 MAX = 1023 + int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg index 4b35bddb9..d5d1fd36f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DENM ::= SEQUENCE { -# header ItsPduHeader, -# denm DecentralizedEnvironmentalNotificationMessage -# } -# ------------------------------------------------------------------------------ +## SEQUENCE DENM ItsPduHeader header + DecentralizedEnvironmentalNotificationMessage denm + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index 4461c2203..b6d9d0329 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousEndOfQueueSubCauseCode ::= INTEGER {unavailable(0), suddenEndOfQueue(1), queueOverHill(2), queueAroundBend(3), queueInTunnel(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER DangerousEndOfQueueSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg index 44ae47a36..df3611bb6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg @@ -1,61 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousGoodsBasic::= ENUMERATED { -# explosives1(0), -# explosives2(1), -# explosives3(2), -# explosives4(3), -# explosives5(4), -# explosives6(5), -# flammableGases(6), -# nonFlammableGases(7), -# toxicGases(8), -# flammableLiquids(9), -# flammableSolids(10), -# substancesLiableToSpontaneousCombustion(11), -# substancesEmittingFlammableGasesUponContactWithWater(12), -# oxidizingSubstances(13), -# organicPeroxides(14), -# toxicSubstances(15), -# infectiousSubstances(16), -# radioactiveMaterial(17), -# corrosiveSubstances(18), -# miscellaneousDangerousSubstances(19) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED DangerousGoodsBasic uint8 value -uint8 EXPLOSIVES_1 = 0 -uint8 EXPLOSIVES_2 = 1 -uint8 EXPLOSIVES_3 = 2 -uint8 EXPLOSIVES_4 = 3 -uint8 EXPLOSIVES_5 = 4 -uint8 EXPLOSIVES_6 = 5 +uint8 EXPLOSIVES1 = 0 +uint8 EXPLOSIVES2 = 1 +uint8 EXPLOSIVES3 = 2 +uint8 EXPLOSIVES4 = 3 +uint8 EXPLOSIVES5 = 4 +uint8 EXPLOSIVES6 = 5 uint8 FLAMMABLE_GASES = 6 uint8 NON_FLAMMABLE_GASES = 7 uint8 TOXIC_GASES = 8 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg index 1b059d622..577cba69f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg @@ -1,65 +1,36 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousGoodsExtended ::= SEQUENCE { -# dangerousGoodsType DangerousGoodsBasic, -# unNumber INTEGER (0..9999), -# elevatedTemperature BOOLEAN, -# tunnelsRestricted BOOLEAN, -# limitedQuantity BOOLEAN, -# emergencyActionCode IA5String (SIZE (1..24)) OPTIONAL, -# phoneNumber PhoneNumber OPTIONAL, -# companyName UTF8String (SIZE (1..24)) OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE DangerousGoodsExtended .extensible DangerousGoodsBasic dangerous_goods_type + uint16 un_number uint16 UN_NUMBER_MIN = 0 uint16 UN_NUMBER_MAX = 9999 bool elevated_temperature + bool tunnels_restricted + bool limited_quantity -string emergency_action_code + bool emergency_action_code_is_present -uint8 EMERGENCY_ACTION_CODE_MIN_SIZE = 1 -uint8 EMERGENCY_ACTION_CODE_MAX_SIZE = 24 +string emergency_action_code +uint8 EMERGENCY_ACTION_CODE_LENGTH_MIN = 1 +uint8 EMERGENCY_ACTION_CODE_LENGTH_MAX = 24 -PhoneNumber phone_number bool phone_number_is_present +PhoneNumber phone_number + -string company_name bool company_name_is_present -uint8 COMPANY_NAME_MIN_SIZE = 1 -uint8 COMPANY_NAME_MAX_SIZE = 24 +string company_name +uint8 COMPANY_NAME_LENGTH_MIN = 1 +uint8 COMPANY_NAME_LENGTH_MAX = 24 + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg index 742d6696b..5c1089ce4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DangerousSituationSubCauseCode ::= INTEGER {unavailable(0), emergencyElectronicBrakeEngaged(1), preCrashSystemEngaged(2), espEngaged(3), absEngaged(4), aebEngaged(5), brakeWarningEngaged(6), collisionRiskWarningEngaged(7)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER DangerousSituationSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 EMERGENCY_ELECTRONIC_BRAKE_ENGAGED = 1 uint8 PRE_CRASH_SYSTEM_ENGAGED = 2 @@ -39,4 +13,3 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg index c35062a0a..347475286 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg @@ -1,46 +1,21 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DecentralizedEnvironmentalNotificationMessage ::= SEQUENCE { -# management ManagementContainer, -# situation SituationContainer OPTIONAL, -# location LocationContainer OPTIONAL, -# alacarte AlacarteContainer OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE DecentralizedEnvironmentalNotificationMessage ManagementContainer management -SituationContainer situation + bool situation_is_present +SituationContainer situation + -LocationContainer location bool location_is_present +LocationContainer location + -AlacarteContainer alacarte bool alacarte_is_present +AlacarteContainer alacarte + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg index e8e7cd2c8..ed6cdfa42 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaAltitude ::= INTEGER {oneCentimeterUp (1), oneCentimeterDown (-1), unavailable(12800)} (-12700..12800) -# ------------------------------------------------------------------------------ +## INTEGER DeltaAltitude int16 value + int16 MIN = -12700 int16 MAX = 12800 + int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg index b4d53fc21..3aaa64597 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaLatitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10) , unavailable(131072)} (-131071..131072) -# ------------------------------------------------------------------------------ +## INTEGER DeltaLatitude int32 value + int32 MIN = -131071 int32 MAX = 131072 + int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg index 09e330c8d..1c61c7b4d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaLongitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(131072)} (-131071..131072) -# ------------------------------------------------------------------------------ +## INTEGER DeltaLongitude int32 value + int32 MIN = -131071 int32 MAX = 131072 + int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg index 687e6a5be..ce78e8e7d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg @@ -1,40 +1,15 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DeltaReferencePosition ::= SEQUENCE { -# deltaLatitude DeltaLatitude, -# deltaLongitude DeltaLongitude, -# deltaAltitude DeltaAltitude -# } -# ------------------------------------------------------------------------------ +## SEQUENCE DeltaReferencePosition DeltaLatitude delta_latitude + DeltaLongitude delta_longitude + DeltaAltitude delta_altitude + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg index d66dfc374..ef631d52d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DigitalMap ::= SEQUENCE (SIZE(1..256)) OF ReferencePosition -# ------------------------------------------------------------------------------ +## SEQUENCE-OF DigitalMap ReferencePosition[] array -uint16 MIN_SIZE = 1 -uint16 MAX_SIZE = 256 - +uint16 LENGTH_MIN = 1 +uint16 LENGTH_MAX = 256 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg index 4bb4caf19..581ffa6dc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DriveDirection ::= ENUMERATED {forward (0), backward (1), unavailable (2)} -# ------------------------------------------------------------------------------ +## ENUMERATED DriveDirection uint8 value uint8 FORWARD = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg index 682d819d3..228db1255 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg @@ -1,35 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# DrivingLaneStatus ::= BIT STRING (SIZE (1..13)) -# ------------------------------------------------------------------------------ +## BIT-STRING DrivingLaneStatus uint8[] value uint8 bits_unused -uint8 MIN_SIZE_BITS = 1 -uint8 MAX_SIZE_BITS = 13 +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 13 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg index 80ae25981..d529b3842 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg @@ -1,32 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmbarkationStatus ::= BOOLEAN -# ------------------------------------------------------------------------------ +## BOOLEAN EmbarkationStatus bool value - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg index 0d7afaae7..b80ba12a6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg @@ -1,36 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmergencyPriority ::= BIT STRING {requestForRightOfWay(0), requestForFreeCrossingAtATrafficLight(1)} (SIZE(2)) -# ------------------------------------------------------------------------------ +## BIT-STRING EmergencyPriority uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 + uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index d88a0b461..73bff4f9a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EmergencyVehicleApproachingSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicleApproaching(1), prioritizedVehicleApproaching(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER EmergencyVehicleApproachingSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg index 104cabb0c..26e57dfde 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EnergyStorageType ::= BIT STRING {hydrogenStorage(0), electricEnergyStorage(1), liquidPropaneGas(2), compressedNaturalGas(3), diesel(4), gasoline(5), ammonia(6)} (SIZE(7)) -# ------------------------------------------------------------------------------ +## BIT-STRING EnergyStorageType uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 + uint8 BIT_INDEX_HYDROGEN_STORAGE = 0 uint8 BIT_INDEX_ELECTRIC_ENERGY_STORAGE = 1 uint8 BIT_INDEX_LIQUID_PROPANE_GAS = 2 @@ -38,4 +11,3 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg index e31ae24c9..be3e6559c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EventHistory::= SEQUENCE (SIZE(1..23)) OF EventPoint -# ------------------------------------------------------------------------------ +## SEQUENCE-OF EventHistory EventPoint[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 23 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 23 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg index c4f7df89c..bf18a2813 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg @@ -1,41 +1,16 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# EventPoint ::= SEQUENCE { -# eventPosition DeltaReferencePosition, -# eventDeltaTime PathDeltaTime OPTIONAL, -# informationQuality InformationQuality -# } -# ------------------------------------------------------------------------------ +## SEQUENCE EventPoint DeltaReferencePosition event_position -PathDeltaTime event_delta_time + bool event_delta_time_is_present +PathDeltaTime event_delta_time + InformationQuality information_quality + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg index ce43d902b..957ddc36b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg @@ -1,45 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ExteriorLights ::= BIT STRING { -# lowBeamHeadlightsOn (0), -# highBeamHeadlightsOn (1), -# leftTurnSignalOn (2), -# rightTurnSignalOn (3), -# daytimeRunningLightsOn (4), -# reverseLightOn (5), -# fogLightOn (6), -# parkingLightsOn (7) -# } (SIZE(8)) -# ------------------------------------------------------------------------------ +## BIT-STRING ExteriorLights uint8[] value uint8 bits_unused uint8 SIZE_BITS = 8 + uint8 BIT_INDEX_LOW_BEAM_HEADLIGHTS_ON = 0 uint8 BIT_INDEX_HIGH_BEAM_HEADLIGHTS_ON = 1 uint8 BIT_INDEX_LEFT_TURN_SIGNAL_ON = 2 @@ -48,4 +12,3 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg index dcb4d381b..460f5aede 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HardShoulderStatus ::= ENUMERATED {availableForStopping(0), closed(1), availableForDriving(2)} -# ------------------------------------------------------------------------------ +## ENUMERATED HardShoulderStatus uint8 value uint8 AVAILABLE_FOR_STOPPING = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 3bffb4cc1..8257e6ff6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-AnimalOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), wildAnimals(1), herdOfAnimals(2), smallAnimals(3), largeAnimals(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index ca7152557..fd2bb3c4c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -1,40 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-DangerousCurveSubCauseCode ::= INTEGER {unavailable(0), dangerousLeftTurnCurve(1), dangerousRightTurnCurve(2), multipleCurvesStartingWithUnknownTurningDirection(3), multipleCurvesStartingWithLeftTurn(4), multipleCurvesStartingWithRightTurn(5)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationDangerousCurveSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 DANGEROUS_LEFT_TURN_CURVE = 1 uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index 4efb4942d..fa3691914 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-ObstacleOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), shedLoad(1), partsOfVehicles(2), partsOfTyres(3), bigObjects(4), fallenTrees(5), hubCaps(6), waitingVehicles(7)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 SHED_LOAD = 1 uint8 PARTS_OF_VEHICLES = 2 @@ -39,4 +13,3 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index d26c8146b..4e8c792aa 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HazardousLocation-SurfaceConditionSubCauseCode ::= INTEGER {unavailable(0), rockfalls(1), earthquakeDamage(2), sewerCollapse(3), subsidence(4), snowDrifts(5), stormDamage(6), burstPipe(7), volcanoEruption(8), fallingIce(9)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HazardousLocationSurfaceConditionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 ROCKFALLS = 1 uint8 EARTHQUAKE_DAMAGE = 2 @@ -41,4 +15,3 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg index 1b545cca4..68df9e493 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Heading ::= SEQUENCE { -# headingValue HeadingValue, -# headingConfidence HeadingConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Heading HeadingValue heading_value + HeadingConfidence heading_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg index 1ee4827f9..4cb626ae0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HeadingConfidence ::= INTEGER {equalOrWithinZeroPointOneDegree (1), equalOrWithinOneDegree (10), outOfRange(126), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER HeadingConfidence uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg index e670dc588..7164cd19b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HeadingValue ::= INTEGER {wgs84North(0), wgs84East(900), wgs84South(1800), wgs84West(2700), unavailable(3601)} (0..3601) -# ------------------------------------------------------------------------------ +## INTEGER HeadingValue uint16 value + uint16 MIN = 0 uint16 MAX = 3601 -uint16 WGS_84_NORTH = 0 -uint16 WGS_84_EAST = 900 -uint16 WGS_84_SOUTH = 1800 -uint16 WGS_84_WEST = 2700 -uint16 UNAVAILABLE = 3601 +uint16 WGS84_NORTH = 0 +uint16 WGS84_EAST = 900 +uint16 WGS84_SOUTH = 1800 +uint16 WGS84_WEST = 2700 +uint16 UNAVAILABLE = 3601 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg index e496a3825..6152a4e51 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HeightLonCarr ::= INTEGER {oneCentimeter(1), unavailable(100)} (1..100) -# ------------------------------------------------------------------------------ +## INTEGER HeightLonCarr uint8 value + uint8 MIN = 1 uint8 MAX = 100 + uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index b3d865712..72163a10c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HumanPresenceOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), childrenOnRoadway(1), cyclistOnRoadway(2), motorcyclistOnRoadway(3)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HumanPresenceOnTheRoadSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg index bde36b417..bf40a01d8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# HumanProblemSubCauseCode ::= INTEGER {unavailable(0), glycemiaProblem(1), heartProblem(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER HumanProblemSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg index 99e840cb4..e7ca74fcd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg @@ -1,67 +1,42 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ImpactReductionContainer ::= SEQUENCE { -# heightLonCarrLeft HeightLonCarr, -# heightLonCarrRight HeightLonCarr, -# posLonCarrLeft PosLonCarr, -# posLonCarrRight PosLonCarr, -# positionOfPillars PositionOfPillars, -# posCentMass PosCentMass, -# wheelBaseVehicle WheelBaseVehicle, -# turningRadius TurningRadius, -# posFrontAx PosFrontAx, -# positionOfOccupants PositionOfOccupants, -# vehicleMass VehicleMass, -# requestResponseIndication RequestResponseIndication -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ImpactReductionContainer HeightLonCarr height_lon_carr_left + HeightLonCarr height_lon_carr_right + PosLonCarr pos_lon_carr_left + PosLonCarr pos_lon_carr_right + PositionOfPillars position_of_pillars + PosCentMass pos_cent_mass + WheelBaseVehicle wheel_base_vehicle + TurningRadius turning_radius + PosFrontAx pos_front_ax + PositionOfOccupants position_of_occupants + VehicleMass vehicle_mass + RequestResponseIndication request_response_indication + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg index cf40d52ab..5af7ec4f4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# InformationQuality ::= INTEGER {unavailable(0), lowest(1), highest(7)} (0..7) -# ------------------------------------------------------------------------------ +## INTEGER InformationQuality uint8 value + uint8 MIN = 0 uint8 MAX = 7 + uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg index c1adc8ce9..15459d1e4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ItineraryPath ::= SEQUENCE SIZE(1..40) OF ReferencePosition -# ------------------------------------------------------------------------------ +## SEQUENCE-OF ItineraryPath ReferencePosition[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 40 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 40 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg index 9957d5f0e..50098612e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg @@ -1,34 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ItsPduHeader ::= SEQUENCE { -# protocolVersion INTEGER (0..255), -# messageID INTEGER{ denm(1), cam(2), poi(3), spatem(4), mapem(5), ivim(6), ev-rsr(7), tistpgtransaction(8), srem(9), ssem(10), evcsn(11), saem(12), rtcmem(13) } (0..255), -- Mantis #7209, #7005 -# ------------------------------------------------------------------------------ +## SEQUENCE ItsPduHeader uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 @@ -53,3 +23,8 @@ uint8 MESSAGE_ID_RTCMEM = 13 StationID station_id + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg index 8ee066832..c2ea265d2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg @@ -1,39 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LanePosition::= INTEGER {offTheRoad(-1), hardShoulder(0), -# outermostDrivingLane(1), secondLaneFromOutside(2)} (-1..14) -# ------------------------------------------------------------------------------ +## INTEGER LanePosition int8 value + int8 MIN = -1 int8 MAX = 14 + int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg index 9ac6f4836..b75736df9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LateralAcceleration ::= SEQUENCE { -# lateralAccelerationValue LateralAccelerationValue, -# lateralAccelerationConfidence AccelerationConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE LateralAcceleration LateralAccelerationValue lateral_acceleration_value + AccelerationConfidence lateral_acceleration_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg index f9b4f8b73..fa022135b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LateralAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredToRight(-1), pointOneMeterPerSecSquaredToLeft(1), unavailable(161)} (-160 .. 161) -# ------------------------------------------------------------------------------ +## INTEGER LateralAccelerationValue int16 value + int16 MIN = -160 int16 MAX = 161 + int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg index 2dc42bbcb..c5be6a7af 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Latitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10), unavailable(900000001)} (-900000000..900000001) -# ------------------------------------------------------------------------------ +## INTEGER Latitude int32 value + int32 MIN = -900000000 int32 MAX = 900000001 + int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg index a9bbe9282..30bb5e2a1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg @@ -1,39 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LightBarSirenInUse ::= BIT STRING { -# lightBarActivated (0), -# sirenActivated (1) -# } (SIZE(2)) -# ------------------------------------------------------------------------------ +## BIT-STRING LightBarSirenInUse uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 + uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg index 85ebfdb29..b8fc171f6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg @@ -1,47 +1,21 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LocationContainer ::= SEQUENCE { -# eventSpeed Speed OPTIONAL, -# eventPositionHeading Heading OPTIONAL, -# traces Traces, -# roadType RoadType OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE LocationContainer .extensible -Speed event_speed bool event_speed_is_present +Speed event_speed + -Heading event_position_heading bool event_position_heading_is_present +Heading event_position_heading + Traces traces -RoadType road_type + bool road_type_is_present +RoadType road_type + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg index 8678c6e5a..bddc707df 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Longitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(1800000001)} (-1800000000..1800000001) -# ------------------------------------------------------------------------------ +## INTEGER Longitude int32 value + int32 MIN = -1800000000 int32 MAX = 1800000001 + int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg index 2950f6914..a56e0c176 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LongitudinalAcceleration ::= SEQUENCE { -# longitudinalAccelerationValue LongitudinalAccelerationValue, -# longitudinalAccelerationConfidence AccelerationConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE LongitudinalAcceleration LongitudinalAccelerationValue longitudinal_acceleration_value + AccelerationConfidence longitudinal_acceleration_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg index ae8f739f8..8b438016e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# LongitudinalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredForward(1), pointOneMeterPerSecSquaredBackward(-1), unavailable(161)} (-160 .. 161) -# ------------------------------------------------------------------------------ +## INTEGER LongitudinalAccelerationValue int16 value + int16 MIN = -160 int16 MAX = 161 + int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg index e764409b4..df0684afa 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg @@ -1,67 +1,41 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ManagementContainer ::= SEQUENCE { -# actionID ActionID, -# detectionTime TimestampIts, -# referenceTime TimestampIts, -# termination Termination OPTIONAL, -# eventPosition ReferencePosition, -# relevanceDistance RelevanceDistance OPTIONAL, -# relevanceTrafficDirection RelevanceTrafficDirection OPTIONAL, -# validityDuration ValidityDuration DEFAULT defaultValidity, -# transmissionInterval TransmissionInterval OPTIONAL, -# stationType StationType, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ManagementContainer .extensible ActionID action_id + TimestampIts detection_time + TimestampIts reference_time -Termination termination + bool termination_is_present +Termination termination + ReferencePosition event_position -RelevanceDistance relevance_distance + bool relevance_distance_is_present +RelevanceDistance relevance_distance + -RelevanceTrafficDirection relevance_traffic_direction bool relevance_traffic_direction_is_present +RelevanceTrafficDirection relevance_traffic_direction + ValidityDuration validity_duration -uint16 DEFAULT_VALIDITY_DURATION = 600 -TransmissionInterval transmission_interval + bool transmission_interval_is_present +TransmissionInterval transmission_interval + StationType station_type + + + + +uint32 VALIDITY_DURATION_DEFAULT = 600 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg index 4cc239cad..1431e2612 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# NumberOfOccupants ::= INTEGER {oneOccupant (1), unavailable(127)} (0 .. 127) -# ------------------------------------------------------------------------------ +## INTEGER NumberOfOccupants uint8 value + uint8 MIN = 0 uint8 MAX = 127 + uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg index bc47f7c8b..843b5354d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg @@ -1,32 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# OpeningDaysHours ::= UTF8String -# ------------------------------------------------------------------------------ +## Utf8String OpeningDaysHours string value - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg index 04ad62a14..d0ecaba0f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## INTEGER PathDeltaTime -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- +int64 value -# --- ASN.1 Definition --------------------------------------------------------- -# PathDeltaTime ::= INTEGER {tenMilliSecondsInPast(1)} (1..65535, ...) -# ------------------------------------------------------------------------------ - -uint16 value -uint16 MIN = 1 -uint16 MAX = 65535 -uint16 TEN_MILLI_SECONDS_IN_PAST = 1 +int64 MIN = 1 +int64 MAX = 65535 +int64 TEN_MILLI_SECONDS_IN_PAST = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg index f45476300..1b3d17250 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PathHistory::= SEQUENCE (SIZE(0..40)) OF PathPoint -# ------------------------------------------------------------------------------ +## SEQUENCE-OF PathHistory PathPoint[] array -uint8 MIN_SIZE = 0 -uint8 MAX_SIZE = 40 - +uint8 LENGTH_MIN = 0 +uint8 LENGTH_MAX = 40 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg index afe56fd92..a3e508126 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg @@ -1,38 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PathPoint ::= SEQUENCE { -# pathPosition DeltaReferencePosition, -# pathDeltaTime PathDeltaTime OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PathPoint DeltaReferencePosition path_position -PathDeltaTime path_delta_time + bool path_delta_time_is_present +PathDeltaTime path_delta_time + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg index 566e6c9ae..9d69f56cd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PerformanceClass ::= INTEGER {unavailable(0), performanceClassA(1), performanceClassB(2)} (0..7) -# ------------------------------------------------------------------------------ +## INTEGER PerformanceClass uint8 value + uint8 MIN = 0 uint8 MAX = 7 + uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg index 6efe47e5d..2d89e9df9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg @@ -1,34 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PhoneNumber ::= NumericString (SIZE(1..16)) -# ------------------------------------------------------------------------------ +## NumericString PhoneNumber string value -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 16 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg index 18fdd9a5c..cfc9cd9bc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosCentMass ::= INTEGER {tenCentimeters(1), unavailable(63)} (1..63) -# ------------------------------------------------------------------------------ +## INTEGER PosCentMass uint8 value + uint8 MIN = 1 uint8 MAX = 63 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg index 0c72b9a6f..0077d220d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg @@ -1,40 +1,15 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosConfidenceEllipse ::= SEQUENCE { -# semiMajorConfidence SemiAxisLength, -# semiMinorConfidence SemiAxisLength, -# semiMajorOrientation HeadingValue -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PosConfidenceEllipse SemiAxisLength semi_major_confidence + SemiAxisLength semi_minor_confidence + HeadingValue semi_major_orientation + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg index 622ab1d0f..13a451247 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosFrontAx ::= INTEGER {tenCentimeters(1), unavailable(20)} (1..20) -# ------------------------------------------------------------------------------ +## INTEGER PosFrontAx uint8 value + uint8 MIN = 1 uint8 MAX = 20 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg index 5d6168e9f..43154206d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosLonCarr ::= INTEGER {oneCentimeter(1), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER PosLonCarr uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg index 050b310d7..b476f8996 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PosPillar ::= INTEGER {tenCentimeters(1), unavailable(30)} (1..30) -# ------------------------------------------------------------------------------ +## INTEGER PosPillar uint8 value + uint8 MIN = 1 uint8 MAX = 30 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg index f11996d64..10c70ae2d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg @@ -1,74 +1,26 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PositionOfOccupants ::= BIT STRING { -# row1LeftOccupied (0), -# row1RightOccupied (1), -# row1MidOccupied (2), -# row1NotDetectable (3), -# row1NotPresent (4), -# row2LeftOccupied (5), -# row2RightOccupied (6), -# row2MidOccupied (7), -# row2NotDetectable (8), -# row2NotPresent (9), -# row3LeftOccupied (10), -# row3RightOccupied (11), -# row3MidOccupied (12), -# row3NotDetectable (13), -# row3NotPresent (14), -# row4LeftOccupied (15), -# row4RightOccupied (16), -# row4MidOccupied (17), -# row4NotDetectable (18), -# row4NotPresent (19)} (SIZE(20)) -# ------------------------------------------------------------------------------ +## BIT-STRING PositionOfOccupants uint8[] value uint8 bits_unused uint8 SIZE_BITS = 20 -uint8 BIT_INDEX_ROW_1_LEFT_OCCUPIED = 0 -uint8 BIT_INDEX_ROW_1_RIGHT_OCCUPIED = 1 -uint8 BIT_INDEX_ROW_1_MID_OCCUPIED = 2 -uint8 BIT_INDEX_ROW_1_NOT_DETECTABLE = 3 -uint8 BIT_INDEX_ROW_1_NOT_PRESENT = 4 -uint8 BIT_INDEX_ROW_2_LEFT_OCCUPIED = 5 -uint8 BIT_INDEX_ROW_2_RIGHT_OCCUPIED = 6 -uint8 BIT_INDEX_ROW_2_MID_OCCUPIED = 7 -uint8 BIT_INDEX_ROW_2_NOT_DETECTABLE = 8 -uint8 BIT_INDEX_ROW_2_NOT_PRESENT = 9 -uint8 BIT_INDEX_ROW_3_LEFT_OCCUPIED = 10 -uint8 BIT_INDEX_ROW_3_RIGHT_OCCUPIED = 11 -uint8 BIT_INDEX_ROW_3_MID_OCCUPIED = 12 -uint8 BIT_INDEX_ROW_3_NOT_DETECTABLE = 13 -uint8 BIT_INDEX_ROW_3_NOT_PRESENT = 14 -uint8 BIT_INDEX_ROW_4_LEFT_OCCUPIED = 15 -uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 -uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 -uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 -uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 +uint8 BIT_INDEX_ROW1_LEFT_OCCUPIED = 0 +uint8 BIT_INDEX_ROW1_RIGHT_OCCUPIED = 1 +uint8 BIT_INDEX_ROW1_MID_OCCUPIED = 2 +uint8 BIT_INDEX_ROW1_NOT_DETECTABLE = 3 +uint8 BIT_INDEX_ROW1_NOT_PRESENT = 4 +uint8 BIT_INDEX_ROW2_LEFT_OCCUPIED = 5 +uint8 BIT_INDEX_ROW2_RIGHT_OCCUPIED = 6 +uint8 BIT_INDEX_ROW2_MID_OCCUPIED = 7 +uint8 BIT_INDEX_ROW2_NOT_DETECTABLE = 8 +uint8 BIT_INDEX_ROW2_NOT_PRESENT = 9 +uint8 BIT_INDEX_ROW3_LEFT_OCCUPIED = 10 +uint8 BIT_INDEX_ROW3_RIGHT_OCCUPIED = 11 +uint8 BIT_INDEX_ROW3_MID_OCCUPIED = 12 +uint8 BIT_INDEX_ROW3_NOT_DETECTABLE = 13 +uint8 BIT_INDEX_ROW3_NOT_PRESENT = 14 +uint8 BIT_INDEX_ROW4_LEFT_OCCUPIED = 15 +uint8 BIT_INDEX_ROW4_RIGHT_OCCUPIED = 16 +uint8 BIT_INDEX_ROW4_MID_OCCUPIED = 17 +uint8 BIT_INDEX_ROW4_NOT_DETECTABLE = 18 +uint8 BIT_INDEX_ROW4_NOT_PRESENT = 19 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg index eea208f31..02b14d0df 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PositionOfPillars ::= SEQUENCE (SIZE(1..3, ...)) OF PosPillar -# ------------------------------------------------------------------------------ +## SEQUENCE-OF PositionOfPillars PosPillar[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 3 - +int64 LENGTH_MIN = 1 +int64 LENGTH_MAX = 3 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg index e0292c4ea..8cfa98a57 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg @@ -1,38 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PositioningSolutionType ::= ENUMERATED {noPositioningSolution(0), sGNSS(1), dGNSS(2), sGNSSplusDR(3), dGNSSplusDR(4), dR(5), ...} -# ------------------------------------------------------------------------------ +## ENUMERATED PositioningSolutionType .extensible uint8 value uint8 NO_POSITIONING_SOLUTION = 0 uint8 S_GNSS = 1 uint8 D_GNSS = 2 -uint8 S_GNSS_PLUS_D_R = 3 -uint8 D_GNSS_PLUS_D_R = 4 +uint8 S_GNS_SPLUS_DR = 3 +uint8 D_GNS_SPLUS_DR = 4 uint8 D_R = 5 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg index bee1a897e..291b9969e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg @@ -1,39 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PostCrashSubCauseCode ::= INTEGER {unavailable(0), accidentWithoutECallTriggered (1), accidentWithECallManuallyTriggered (2), accidentWithECallAutomaticallyTriggered (3), accidentWithECallTriggeredWithoutAccessToCellularNetwork(4)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER PostCrashSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg index 5a6ebbbd4..335f5fcc2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg @@ -1,53 +1,27 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedCommunicationZone ::= SEQUENCE { -# protectedZoneType ProtectedZoneType, -# expiryTime TimestampIts OPTIONAL, -# protectedZoneLatitude Latitude, -# protectedZoneLongitude Longitude, -# protectedZoneRadius ProtectedZoneRadius OPTIONAL, -# protectedZoneID ProtectedZoneID OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ProtectedCommunicationZone .extensible ProtectedZoneType protected_zone_type -TimestampIts expiry_time + bool expiry_time_is_present +TimestampIts expiry_time + Latitude protected_zone_latitude + Longitude protected_zone_longitude -ProtectedZoneRadius protected_zone_radius + bool protected_zone_radius_is_present +ProtectedZoneRadius protected_zone_radius + -ProtectedZoneID protected_zone_id bool protected_zone_id_is_present +ProtectedZoneID protected_zone_id + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg index cc6d8ea62..3e68a4b85 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedCommunicationZonesRSU ::= SEQUENCE (SIZE(1..16)) OF ProtectedCommunicationZone -# ------------------------------------------------------------------------------ +## SEQUENCE-OF ProtectedCommunicationZonesRSU ProtectedCommunicationZone[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 16 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 16 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg index 6a0344d74..8ad38e935 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedZoneID ::= INTEGER (0.. 134217727) -# ------------------------------------------------------------------------------ +## INTEGER ProtectedZoneID uint32 value + uint32 MIN = 0 uint32 MAX = 134217727 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg index 7f1a3f2c2..e5fce0ff6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== +## INTEGER ProtectedZoneRadius -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- +int64 value -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedZoneRadius ::= INTEGER {oneMeter(1)} (1..255,...) -# ------------------------------------------------------------------------------ - -uint8 value -uint8 MIN = 1 -uint8 MAX = 255 -uint8 ONE_METER = 1 +int64 MIN = 1 +int64 MAX = 255 +int64 ONE_METER = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg index 3283db4e0..277c99b9a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ProtectedZoneType::= ENUMERATED { permanentCenDsrcTolling (0), ..., temporaryCenDsrcTolling (1) } -# ------------------------------------------------------------------------------ +## ENUMERATED ProtectedZoneType .extensible uint8 value uint8 PERMANENT_CEN_DSRC_TOLLING = 0 +# .extended uint8 TEMPORARY_CEN_DSRC_TOLLING = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg index f70514140..b067e6f81 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PtActivation ::= SEQUENCE { -# ptActivationType PtActivationType, -# ptActivationData PtActivationData -# } -# ------------------------------------------------------------------------------ +## SEQUENCE PtActivation PtActivationType pt_activation_type + PtActivationData pt_activation_data + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg index 0fb3a6413..9e0108cdf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg @@ -1,34 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PtActivationData ::= OCTET STRING (SIZE(1..20)) -# ------------------------------------------------------------------------------ +## OCTET-STRING PtActivationData uint8[] value -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 20 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg index 0d373552c..dbf87a49d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# PtActivationType ::= INTEGER {undefinedCodingType(0), r09-16CodingType(1), vdv-50149CodingType(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER PtActivationType uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNDEFINED_CODING_TYPE = 0 -uint8 R_09_16_CODING_TYPE = 1 +uint8 R09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg index bedf5e7f1..b78dcf946 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ReferenceDenms ::= SEQUENCE (SIZE(1..8, ...)) OF ActionID -# ------------------------------------------------------------------------------ +## SEQUENCE-OF ReferenceDenms ActionID[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 8 - +int64 LENGTH_MIN = 1 +int64 LENGTH_MAX = 8 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg index ff37f4ebf..2e15eb7bd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg @@ -1,43 +1,18 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ReferencePosition ::= SEQUENCE { -# latitude Latitude, -# longitude Longitude, -# positionConfidenceEllipse PosConfidenceEllipse , -# altitude Altitude -# } -# ------------------------------------------------------------------------------ +## SEQUENCE ReferencePosition Latitude latitude + Longitude longitude + PosConfidenceEllipse position_confidence_ellipse + Altitude altitude + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg index 03f962736..52210df13 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg @@ -1,40 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RelevanceDistance ::= ENUMERATED {lessThan50m(0), lessThan100m(1), lessThan200m(2), lessThan500m(3), lessThan1000m(4), lessThan5km(5), lessThan10km(6), over10km(7)} -# ------------------------------------------------------------------------------ +## ENUMERATED RelevanceDistance uint8 value -uint8 LESS_THAN_50M = 0 -uint8 LESS_THAN_100M = 1 -uint8 LESS_THAN_200M = 2 -uint8 LESS_THAN_500M = 3 -uint8 LESS_THAN_1000M = 4 -uint8 LESS_THAN_5KM = 5 -uint8 LESS_THAN_10KM = 6 -uint8 OVER_10KM = 7 +uint8 LESS_THAN50M = 0 +uint8 LESS_THAN100M = 1 +uint8 LESS_THAN200M = 2 +uint8 LESS_THAN500M = 3 +uint8 LESS_THAN1000M = 4 +uint8 LESS_THAN5KM = 5 +uint8 LESS_THAN10KM = 6 +uint8 OVER10KM = 7 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg index 6a2060b60..1b942c3ed 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RelevanceTrafficDirection ::= ENUMERATED {allTrafficDirections(0), upstreamTraffic(1), downstreamTraffic(2), oppositeTraffic(3)} -# ------------------------------------------------------------------------------ +## ENUMERATED RelevanceTrafficDirection uint8 value uint8 ALL_TRAFFIC_DIRECTIONS = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg index e87b70032..45e45c756 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RequestResponseIndication ::= ENUMERATED {request(0), response(1)} -# ------------------------------------------------------------------------------ +## ENUMERATED RequestResponseIndication uint8 value uint8 REQUEST = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index 3cd20fa4f..bacf1a7ea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -1,40 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RescueAndRecoveryWorkInProgressSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicles(1), rescueHelicopterLanding(2), policeActivityOngoing(3), medicalEmergencyOngoing(4), childAbductionInProgress(5)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLES = 1 uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg index d5103c64e..61e48f1e6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RestrictedTypes ::= SEQUENCE (SIZE(1..3, ...)) OF StationType -# ------------------------------------------------------------------------------ +## SEQUENCE-OF RestrictedTypes StationType[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 3 - +int64 LENGTH_MIN = 1 +int64 LENGTH_MAX = 3 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg index e2615acec..dd2e542e7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg @@ -1,36 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RoadType ::= ENUMERATED { -# urban-NoStructuralSeparationToOppositeLanes(0), -# urban-WithStructuralSeparationToOppositeLanes(1), -# nonUrban-NoStructuralSeparationToOppositeLanes(2), -# nonUrban-WithStructuralSeparationToOppositeLanes(3)} -# ------------------------------------------------------------------------------ +## ENUMERATED RoadType uint8 value uint8 URBAN_NO_STRUCTURAL_SEPARATION_TO_OPPOSITE_LANES = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg index 7948b4d6a..d498b926f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg @@ -1,67 +1,42 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RoadWorksContainerExtended ::= SEQUENCE { -# lightBarSirenInUse LightBarSirenInUse OPTIONAL, -# closedLanes ClosedLanes OPTIONAL, -# restriction RestrictedTypes OPTIONAL, -# speedLimit SpeedLimit OPTIONAL, -# incidentIndication CauseCode OPTIONAL, -# recommendedPath ItineraryPath OPTIONAL, -# startingPointSpeedLimit DeltaReferencePosition OPTIONAL, -# trafficFlowRule TrafficRule OPTIONAL, -# referenceDenms ReferenceDenms OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE RoadWorksContainerExtended -LightBarSirenInUse light_bar_siren_in_use bool light_bar_siren_in_use_is_present +LightBarSirenInUse light_bar_siren_in_use + -ClosedLanes closed_lanes bool closed_lanes_is_present +ClosedLanes closed_lanes + -RestrictedTypes restriction bool restriction_is_present +RestrictedTypes restriction + -SpeedLimit speed_limit bool speed_limit_is_present +SpeedLimit speed_limit + -CauseCode incident_indication bool incident_indication_is_present +CauseCode incident_indication + -ItineraryPath recommended_path bool recommended_path_is_present +ItineraryPath recommended_path + -DeltaReferencePosition starting_point_speed_limit bool starting_point_speed_limit_is_present +DeltaReferencePosition starting_point_speed_limit + -TrafficRule traffic_flow_rule bool traffic_flow_rule_is_present +TrafficRule traffic_flow_rule + -ReferenceDenms reference_denms bool reference_denms_is_present +ReferenceDenms reference_denms + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg index 153e11c4e..20057cc6a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# RoadworksSubCauseCode ::= INTEGER {unavailable(0), majorRoadworks(1), roadMarkingWork(2), slowMovingRoadMaintenance(3), shortTermStationaryRoadworks(4), streetCleaning(5), winterService(6)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER RoadworksSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 MAJOR_ROADWORKS = 1 uint8 ROAD_MARKING_WORK = 2 @@ -38,4 +12,3 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg index 976c006d8..083e860ab 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SemiAxisLength ::= INTEGER{oneCentimeter(1), outOfRange(4094), unavailable(4095)} (0..4095) -# ------------------------------------------------------------------------------ +## INTEGER SemiAxisLength uint16 value + uint16 MIN = 0 uint16 MAX = 4095 + uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg index 3ee9128cd..5171880d2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SequenceNumber ::= INTEGER (0..65535) -# ------------------------------------------------------------------------------ +## INTEGER SequenceNumber uint16 value + uint16 MIN = 0 uint16 MAX = 65535 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg index 580af19c9..a7d121127 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SignalViolationSubCauseCode ::= INTEGER {unavailable(0), stopSignViolation(1), trafficLightViolation(2), turningRegulationViolation(3)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER SignalViolationSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg index f0bc862ea..4f6c47bcb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg @@ -1,46 +1,20 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SituationContainer ::= SEQUENCE { -# informationQuality InformationQuality, -# eventType CauseCode, -# linkedCause CauseCode OPTIONAL, -# eventHistory EventHistory OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ +## SEQUENCE SituationContainer .extensible InformationQuality information_quality + CauseCode event_type -CauseCode linked_cause + bool linked_cause_is_present +CauseCode linked_cause + -EventHistory event_history bool event_history_is_present +EventHistory event_history + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg index d7c7e96b7..131897657 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SlowVehicleSubCauseCode ::= INTEGER {unavailable(0), maintenanceVehicle(1), vehiclesSlowingToLookAtAccident(2), abnormalLoad(3), abnormalWideLoad(4), convoy(5), snowplough(6), deicing(7), saltingVehicles(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER SlowVehicleSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 MAINTENANCE_VEHICLE = 1 uint8 VEHICLES_SLOWING_TO_LOOK_AT_ACCIDENT = 2 @@ -40,4 +14,3 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg index 8f5fcd9d6..ca8a3f72a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg @@ -1,38 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpecialTransportType ::= BIT STRING {heavyLoad(0), excessWidth(1), excessLength(2), excessHeight(3)} (SIZE(4)) -# ------------------------------------------------------------------------------ +## BIT-STRING SpecialTransportType uint8[] value uint8 bits_unused uint8 SIZE_BITS = 4 + uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg index ecfc591e4..cac581f03 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Speed ::= SEQUENCE { -# speedValue SpeedValue, -# speedConfidence SpeedConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE Speed SpeedValue speed_value + SpeedConfidence speed_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg index 487873b36..34a84c0fc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpeedConfidence ::= INTEGER {equalOrWithinOneCentimeterPerSec(1), equalOrWithinOneMeterPerSec(100), outOfRange(126), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER SpeedConfidence uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg index 4cf1a9d03..3a459e7ce 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg @@ -1,35 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpeedLimit ::= INTEGER {oneKmPerHour(1)} (1..255) -# ------------------------------------------------------------------------------ +## INTEGER SpeedLimit uint8 value + uint8 MIN = 1 uint8 MAX = 255 -uint8 ONE_KM_PER_HOUR = 1 +uint8 ONE_KM_PER_HOUR = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg index b3d89beff..e18097a0f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SpeedValue ::= INTEGER {standstill(0), oneCentimeterPerSec(1), unavailable(16383)} (0..16383) -# ------------------------------------------------------------------------------ +## INTEGER SpeedValue uint16 value + uint16 MIN = 0 uint16 MAX = 16383 + uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg index 9d36a5a65..f49d34323 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationID ::= INTEGER(0..4294967295) -# ------------------------------------------------------------------------------ +## INTEGER StationID uint32 value + uint32 MIN = 0 uint32 MAX = 4294967295 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg index 104c6821e..e91775578 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationType ::= INTEGER {unknown(0), pedestrian(1), cyclist(2), moped(3), motorcycle(4), passengerCar(5), bus(6), -# lightTruck(7), heavyTruck(8), trailer(9), specialVehicles(10), tram(11), roadSideUnit(15)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER StationType uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNKNOWN = 0 uint8 PEDESTRIAN = 1 uint8 CYCLIST = 2 @@ -45,4 +18,3 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg index e0133c7a8..80b7c9660 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg @@ -1,36 +1,8 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationarySince ::= ENUMERATED {lessThan1Minute(0), lessThan2Minutes(1), lessThan15Minutes(2), equalOrGreater15Minutes(3)} -# ------------------------------------------------------------------------------ +## ENUMERATED StationarySince uint8 value -uint8 LESS_THAN_1_MINUTE = 0 -uint8 LESS_THAN_2_MINUTES = 1 -uint8 LESS_THAN_15_MINUTES = 2 -uint8 EQUAL_OR_GREATER_15_MINUTES = 3 +uint8 LESS_THAN1_MINUTE = 0 +uint8 LESS_THAN2_MINUTES = 1 +uint8 LESS_THAN15_MINUTES = 2 +uint8 EQUAL_OR_GREATER15_MINUTES = 3 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg index 07c536a89..9377af699 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg @@ -1,55 +1,30 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationaryVehicleContainer ::= SEQUENCE { -# stationarySince StationarySince OPTIONAL, -# stationaryCause CauseCode OPTIONAL, -# carryingDangerousGoods DangerousGoodsExtended OPTIONAL, -# numberOfOccupants NumberOfOccupants OPTIONAL, -# vehicleIdentification VehicleIdentification OPTIONAL, -# energyStorageType EnergyStorageType OPTIONAL -# } -# ------------------------------------------------------------------------------ +## SEQUENCE StationaryVehicleContainer -StationarySince stationary_since bool stationary_since_is_present +StationarySince stationary_since + -CauseCode stationary_cause bool stationary_cause_is_present +CauseCode stationary_cause + -DangerousGoodsExtended carrying_dangerous_goods bool carrying_dangerous_goods_is_present +DangerousGoodsExtended carrying_dangerous_goods + -NumberOfOccupants number_of_occupants bool number_of_occupants_is_present +NumberOfOccupants number_of_occupants + -VehicleIdentification vehicle_identification bool vehicle_identification_is_present +VehicleIdentification vehicle_identification + -EnergyStorageType energy_storage_type bool energy_storage_type_is_present +EnergyStorageType energy_storage_type + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg index 190a7c78e..c48785887 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -1,40 +1,13 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# StationaryVehicleSubCauseCode ::= INTEGER {unavailable(0), humanProblem(1), vehicleBreakdown(2), postCrash(3), publicTransportStop(4), carryingDangerousGoods(5)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER StationaryVehicleSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 HUMAN_PROBLEM = 1 uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg index 918cc7a8d..76e9ef597 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SteeringWheelAngle ::= SEQUENCE { -# steeringWheelAngleValue SteeringWheelAngleValue, -# steeringWheelAngleConfidence SteeringWheelAngleConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE SteeringWheelAngle SteeringWheelAngleValue steering_wheel_angle_value + SteeringWheelAngleConfidence steering_wheel_angle_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg index bf209a62e..dbd12e458 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SteeringWheelAngleConfidence ::= INTEGER {equalOrWithinOnePointFiveDegree (1), outOfRange(126), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER SteeringWheelAngleConfidence uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg index fbda5ff63..9b04cdf9f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SteeringWheelAngleValue ::= INTEGER {straight(0), onePointFiveDegreesToRight(-1), onePointFiveDegreesToLeft(1), unavailable(512)} (-511..512) -# ------------------------------------------------------------------------------ +## INTEGER SteeringWheelAngleValue int16 value + int16 MIN = -511 int16 MAX = 512 + int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg index 5f328fa69..b08a83005 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg @@ -1,34 +1,7 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# SubCauseCodeType ::= INTEGER (0..255) -# ------------------------------------------------------------------------------ +## INTEGER SubCauseCodeType uint8 value + uint8 MIN = 0 uint8 MAX = 255 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg index 2e351568e..f2a497ef5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Temperature ::= INTEGER {equalOrSmallerThanMinus60Deg (-60), oneDegreeCelsius(1), equalOrGreaterThan67Deg(67)} (-60..67) -# ------------------------------------------------------------------------------ +## INTEGER Temperature int8 value + int8 MIN = -60 int8 MAX = 67 -int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 -int8 ONE_DEGREE_CELSIUS = 1 -int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 +int8 EQUAL_OR_SMALLER_THAN_MINUS60_DEG = -60 +int8 ONE_DEGREE_CELSIUS = 1 +int8 EQUAL_OR_GREATER_THAN67_DEG = 67 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg index 33ac2d5dd..a2b23ce05 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Termination ::= ENUMERATED {isCancellation(0), isNegation (1)} -# ------------------------------------------------------------------------------ +## ENUMERATED Termination uint8 value uint8 IS_CANCELLATION = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg index 6871563ba..342fcf26b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TimestampIts ::= INTEGER {utcStartOf2004(0), oneMillisecAfterUTCStartOf2004(1)} (0..4398046511103) -# ------------------------------------------------------------------------------ +## INTEGER TimestampIts uint64 value + uint64 MIN = 0 uint64 MAX = 4398046511103 -uint64 UTC_START_OF_2004 = 0 -uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 +uint64 UTC_START_OF2004 = 0 +uint64 ONE_MILLISEC_AFTER_UTC_START_OF2004 = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg index db7a2bb0f..479157e9d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg @@ -1,34 +1,5 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# Traces ::= SEQUENCE SIZE(1..7) OF PathHistory -# ------------------------------------------------------------------------------ +## SEQUENCE-OF Traces PathHistory[] array -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 7 - +uint8 LENGTH_MIN = 1 +uint8 LENGTH_MAX = 7 \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg index 38061b4a4..c060c7ebc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TrafficConditionSubCauseCode ::= INTEGER {unavailable(0), increasedVolumeOfTraffic(1), trafficJamSlowlyIncreasing(2), trafficJamIncreasing(3), trafficJamStronglyIncreasing(4), trafficStationary(5), trafficJamSlightlyDecreasing(6), trafficJamDecreasing(7), trafficJamStronglyDecreasing(8)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER TrafficConditionSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 INCREASED_VOLUME_OF_TRAFFIC = 1 uint8 TRAFFIC_JAM_SLOWLY_INCREASING = 2 @@ -40,4 +14,3 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg index cc8afc852..e138ac055 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg @@ -1,33 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TrafficRule ::= ENUMERATED {noPassing(0), noPassingForTrucks(1), passToRight(2), passToLeft(3), ... -# } -# ------------------------------------------------------------------------------ +## ENUMERATED TrafficRule .extensible uint8 value uint8 NO_PASSING = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg index 343d094dd..e505df9b5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TransmissionInterval ::= INTEGER {oneMilliSecond(1), tenSeconds(10000)} (1..10000) -# ------------------------------------------------------------------------------ +## INTEGER TransmissionInterval uint16 value + uint16 MIN = 1 uint16 MAX = 10000 + uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg index 99ccaa91d..11de9132c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# TurningRadius ::= INTEGER {point4Meters(1), unavailable(255)} (1..255) -# ------------------------------------------------------------------------------ +## INTEGER TurningRadius uint8 value + uint8 MIN = 1 uint8 MAX = 255 -uint8 POINT_4_METERS = 1 -uint8 UNAVAILABLE = 255 +uint8 POINT4_METERS = 1 +uint8 UNAVAILABLE = 255 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg index e9beb0f3f..b08a5c238 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg @@ -1,33 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VDS ::= IA5String (SIZE(6)) -# ------------------------------------------------------------------------------ +## Ia5String VDS string value -uint8 SIZE = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg index 3cfc6ffe7..d11827ef1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# ValidityDuration ::= INTEGER {timeOfDetection(0), oneSecondAfterDetection(1)} (0..86400) -# ------------------------------------------------------------------------------ +## INTEGER ValidityDuration uint32 value + uint32 MIN = 0 uint32 MAX = 86400 + uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg index 40c794fa4..ef3d2d1c6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -1,36 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleBreakdownSubCauseCode ::= INTEGER {unavailable(0), lackOfFuel (1), lackOfBatteryPower (2), engineProblem(3), transmissionProblem(4), engineCoolingProblem(5), brakingSystemProblem(6), steeringProblem(7), tyrePuncture(8), tyrePressureProblem(9)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER VehicleBreakdownSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 LACK_OF_FUEL = 1 uint8 LACK_OF_BATTERY_POWER = 2 @@ -41,4 +15,3 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg index 411ade20f..1b7b25c07 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg @@ -1,40 +1,14 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleIdentification ::= SEQUENCE { -# wMInumber WMInumber OPTIONAL, -# vDS VDS OPTIONAL, -# ... -# } -# ------------------------------------------------------------------------------ - -WMInumber wm_inumber -bool wm_inumber_is_present - -VDS vds -bool vds_is_present +## SEQUENCE VehicleIdentification .extensible + +bool w_m_inumber_is_present +WMInumber w_m_inumber + + +bool v_ds_is_present +VDS v_ds + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg index 0657adbdc..543253116 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleLength ::= SEQUENCE { -# vehicleLengthValue VehicleLengthValue, -# vehicleLengthConfidenceIndication VehicleLengthConfidenceIndication -# } -# ------------------------------------------------------------------------------ +## SEQUENCE VehicleLength VehicleLengthValue vehicle_length_value + VehicleLengthConfidenceIndication vehicle_length_confidence_indication + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg index b5a008bba..5cd4611f7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleLengthConfidenceIndication ::= ENUMERATED {noTrailerPresent(0), trailerPresentWithKnownLength(1), trailerPresentWithUnknownLength(2), trailerPresenceIsUnknown(3), unavailable(4)} -# ------------------------------------------------------------------------------ +## ENUMERATED VehicleLengthConfidenceIndication uint8 value uint8 NO_TRAILER_PRESENT = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg index e253cfda3..2c2bc6e87 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleLengthValue ::= INTEGER {tenCentimeters(1), outOfRange(1022), unavailable(1023)} (1..1023) -# ------------------------------------------------------------------------------ +## INTEGER VehicleLengthValue uint16 value + uint16 MIN = 1 uint16 MAX = 1023 + uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg index d74f09b5c..949dc93b2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleMass ::= INTEGER {hundredKg(1), unavailable(1024)} (1..1024) -# ------------------------------------------------------------------------------ +## INTEGER VehicleMass uint16 value + uint16 MIN = 1 uint16 MAX = 1024 + uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg index daeb43921..dee2e6e66 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg @@ -1,32 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleRole ::= ENUMERATED {default(0), publicTransport(1), specialTransport(2), dangerousGoods(3), roadWork(4), rescue(5), emergency(6), safetyCar(7), agriculture(8), commercial(9), military(10), roadOperator(11), taxi(12), reserved1(13), reserved2(14), reserved3(15)} -# ------------------------------------------------------------------------------ +## ENUMERATED VehicleRole uint8 value uint8 DEFAULT = 0 @@ -42,7 +14,7 @@ uint8 COMMERCIAL = 9 uint8 MILITARY = 10 uint8 ROAD_OPERATOR = 11 uint8 TAXI = 12 -uint8 RESERVED_1 = 13 -uint8 RESERVED_2 = 14 -uint8 RESERVED_3 = 15 +uint8 RESERVED1 = 13 +uint8 RESERVED2 = 14 +uint8 RESERVED3 = 15 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg index c209c3b57..0ff4d5cee 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VehicleWidth ::= INTEGER {tenCentimeters(1), outOfRange(61), unavailable(62)} (1..62) -# ------------------------------------------------------------------------------ +## INTEGER VehicleWidth uint8 value + uint8 MIN = 1 uint8 MAX = 62 + uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg index 3da431c59..c6927a06c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VerticalAcceleration ::= SEQUENCE { -# verticalAccelerationValue VerticalAccelerationValue, -# verticalAccelerationConfidence AccelerationConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE VerticalAcceleration VerticalAccelerationValue vertical_acceleration_value + AccelerationConfidence vertical_acceleration_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg index 4f208993e..2267e732c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# VerticalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredUp(1), pointOneMeterPerSecSquaredDown(-1), unavailable(161)} (-160 .. 161) -# ------------------------------------------------------------------------------ +## INTEGER VerticalAccelerationValue int16 value + int16 MIN = -160 int16 MAX = 161 + int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg index 34b682f9a..fef01bdbf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg @@ -1,34 +1,3 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# WMInumber ::= IA5String (SIZE(1..3)) -# ------------------------------------------------------------------------------ +## Ia5String WMInumber string value -uint8 MIN_SIZE = 1 -uint8 MAX_SIZE = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg index af24dccaf..4a9feb773 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg @@ -1,36 +1,9 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# WheelBaseVehicle ::= INTEGER {tenCentimeters(1), unavailable(127)} (1..127) -# ------------------------------------------------------------------------------ +## INTEGER WheelBaseVehicle uint8 value + uint8 MIN = 1 uint8 MAX = 127 + uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg index 0f8080f05..4ee06efd1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -1,37 +1,10 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# WrongWayDrivingSubCauseCode ::= INTEGER {unavailable(0), wrongLane(1), wrongDirection(2)} (0..255) -# ------------------------------------------------------------------------------ +## INTEGER WrongWayDrivingSubCauseCode uint8 value + uint8 MIN = 0 uint8 MAX = 255 + uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg index 2284e9ba8..69e8f08eb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg @@ -1,37 +1,12 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# YawRate::= SEQUENCE { -# yawRateValue YawRateValue, -# yawRateConfidence YawRateConfidence -# } -# ------------------------------------------------------------------------------ +## SEQUENCE YawRate YawRateValue yaw_rate_value + YawRateConfidence yaw_rate_confidence + + + + + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg index 4150e4776..72f3c0bf8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg @@ -1,42 +1,4 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# YawRateConfidence ::= ENUMERATED { -# degSec-000-01 (0), -# degSec-000-05 (1), -# degSec-000-10 (2), -# degSec-001-00 (3), -# degSec-005-00 (4), -# degSec-010-00 (5), -# degSec-100-00 (6), -# outOfRange (7), -# unavailable (8) -# } -# ------------------------------------------------------------------------------ +## ENUMERATED YawRateConfidence uint8 value uint8 DEG_SEC_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg index 9564c6bee..8c0e228b7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg @@ -1,38 +1,11 @@ -# ============================================================================== -# MIT License -# -# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# -# Permission is hereby granted, free of charge, to any person obtaining a copy -# of this software and associated documentation files (the "Software"), to deal -# in the Software without restriction, including without limitation the rights -# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -# copies of the Software, and to permit persons to whom the Software is -# furnished to do so, subject to the following conditions: -# -# The above copyright notice and this permission notice shall be included in all -# copies or substantial portions of the Software. -# -# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -# SOFTWARE. -# ============================================================================== - -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - -# --- ASN.1 Definition --------------------------------------------------------- -# YawRateValue ::= INTEGER {straight(0), degSec-000-01ToRight(-1), degSec-000-01ToLeft(1), unavailable(32767)} (-32766..32767) -# ------------------------------------------------------------------------------ +## INTEGER YawRateValue int16 value + int16 MIN = -32766 int16 MAX = 32767 + int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 - From 28cf6d1d9caf99f286fec766f94941ec9fd3ee83 Mon Sep 17 00:00:00 2001 From: v0-e Date: Thu, 16 May 2024 13:50:19 +0100 Subject: [PATCH 09/22] rgen: Add VS Code .msgs, conversion headers CAM/DENM setups --- .vscode/launch.json | 58 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 58 insertions(+) diff --git a/.vscode/launch.json b/.vscode/launch.json index e6090e935..6c25ad89e 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -88,5 +88,63 @@ "justMyCode": true }, + { + "name": "CAM asn1ToRosMsg (rgen)", + "type": "python", + "request": "launch", + "program": "utils/codegen/asn1ToRosMsg-rgen.py", + "args": [ + "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", + "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", + "-o", "etsi_its_msgs/etsi_its_cam_msgs/msg" + ], + "console": "integratedTerminal", + "justMyCode": true + }, + + { + "name": "DENM asn1ToRosMsg (rgen)", + "type": "python", + "request": "launch", + "program": "utils/codegen/asn1ToRosMsg-rgen.py", + "args": [ + "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", + "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", + "-o", "etsi_its_msgs/etsi_its_denm_msgs/msg" + ], + "console": "integratedTerminal", + "justMyCode": true + }, + + { + "name": "CAM asn1ToConversionHeader (rgen)", + "type": "python", + "request": "launch", + "program": "utils/codegen/asn1ToConversionHeader-rgen.py", + "args": [ + "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", + "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", + "-t", "cam", + "-o", "etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion" + ], + "console": "integratedTerminal", + "justMyCode": true + }, + + { + "name": "DENM asn1ToConversionHeader (rgen)", + "type": "python", + "request": "launch", + "program": "utils/codegen/asn1ToConversionHeader-rgen.py", + "args": [ + "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", + "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", + "-t", "denm", + "-o", "etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion" + ], + "console": "integratedTerminal", + "justMyCode": true + }, + ] } From b4e41988ac0499d9d9aee92bab60d80ed550f406 Mon Sep 17 00:00:00 2001 From: v0-e Date: Mon, 3 Jun 2024 17:41:02 +0100 Subject: [PATCH 10/22] rgen: Include license --- .../convertAccelerationConfidence.h | 27 +++++++ .../convertAccelerationControl.h | 27 +++++++ .../convertAccidentSubCauseCode.h | 27 +++++++ .../etsi_its_cam_conversion/convertActionID.h | 27 +++++++ ...erseWeatherConditionAdhesionSubCauseCode.h | 27 +++++++ ...itionExtremeWeatherConditionSubCauseCode.h | 27 +++++++ ...eatherConditionPrecipitationSubCauseCode.h | 27 +++++++ ...seWeatherConditionVisibilitySubCauseCode.h | 27 +++++++ .../etsi_its_cam_conversion/convertAltitude.h | 27 +++++++ .../convertAltitudeConfidence.h | 27 +++++++ .../convertAltitudeValue.h | 27 +++++++ .../convertBasicContainer.h | 27 +++++++ ...onvertBasicVehicleContainerHighFrequency.h | 27 +++++++ ...convertBasicVehicleContainerLowFrequency.h | 27 +++++++ .../etsi_its_cam_conversion/convertCAM.h | 27 +++++++ .../convertCamParameters.h | 27 +++++++ .../convertCauseCode.h | 27 +++++++ .../convertCauseCodeType.h | 27 +++++++ .../convertCenDsrcTollingZone.h | 27 +++++++ .../convertCenDsrcTollingZoneID.h | 27 +++++++ .../convertClosedLanes.h | 27 +++++++ .../convertCollisionRiskSubCauseCode.h | 27 +++++++ .../convertCoopAwareness.h | 27 +++++++ .../convertCurvature.h | 27 +++++++ .../convertCurvatureCalculationMode.h | 27 +++++++ .../convertCurvatureConfidence.h | 27 +++++++ .../convertCurvatureValue.h | 27 +++++++ .../convertDangerousEndOfQueueSubCauseCode.h | 27 +++++++ .../convertDangerousGoodsBasic.h | 27 +++++++ .../convertDangerousGoodsContainer.h | 27 +++++++ .../convertDangerousGoodsExtended.h | 27 +++++++ .../convertDangerousSituationSubCauseCode.h | 27 +++++++ .../convertDeltaAltitude.h | 27 +++++++ .../convertDeltaLatitude.h | 27 +++++++ .../convertDeltaLongitude.h | 27 +++++++ .../convertDeltaReferencePosition.h | 27 +++++++ .../convertDigitalMap.h | 27 +++++++ .../convertDriveDirection.h | 27 +++++++ .../convertDrivingLaneStatus.h | 27 +++++++ .../convertEmbarkationStatus.h | 27 +++++++ .../convertEmergencyContainer.h | 27 +++++++ .../convertEmergencyPriority.h | 27 +++++++ ...tEmergencyVehicleApproachingSubCauseCode.h | 27 +++++++ .../convertEnergyStorageType.h | 27 +++++++ .../convertEventHistory.h | 27 +++++++ .../convertEventPoint.h | 27 +++++++ .../convertExteriorLights.h | 27 +++++++ .../convertGenerationDeltaTime.h | 27 +++++++ .../convertHardShoulderStatus.h | 27 +++++++ ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 27 +++++++ ...ardousLocationDangerousCurveSubCauseCode.h | 27 +++++++ ...ousLocationObstacleOnTheRoadSubCauseCode.h | 27 +++++++ ...dousLocationSurfaceConditionSubCauseCode.h | 27 +++++++ .../etsi_its_cam_conversion/convertHeading.h | 27 +++++++ .../convertHeadingConfidence.h | 27 +++++++ .../convertHeadingValue.h | 27 +++++++ .../convertHeightLonCarr.h | 27 +++++++ .../convertHighFrequencyContainer.h | 27 +++++++ ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 27 +++++++ .../convertHumanProblemSubCauseCode.h | 27 +++++++ .../convertInformationQuality.h | 27 +++++++ .../convertItineraryPath.h | 27 +++++++ .../convertItsPduHeader.h | 27 +++++++ .../convertLanePosition.h | 27 +++++++ .../convertLateralAcceleration.h | 27 +++++++ .../convertLateralAccelerationValue.h | 27 +++++++ .../etsi_its_cam_conversion/convertLatitude.h | 27 +++++++ .../convertLightBarSirenInUse.h | 27 +++++++ .../convertLongitude.h | 27 +++++++ .../convertLongitudinalAcceleration.h | 27 +++++++ .../convertLongitudinalAccelerationValue.h | 27 +++++++ .../convertLowFrequencyContainer.h | 27 +++++++ .../convertNumberOfOccupants.h | 27 +++++++ .../convertOpeningDaysHours.h | 27 +++++++ .../convertPathDeltaTime.h | 27 +++++++ .../convertPathHistory.h | 27 +++++++ .../convertPathPoint.h | 27 +++++++ .../convertPerformanceClass.h | 27 +++++++ .../convertPhoneNumber.h | 27 +++++++ .../convertPosCentMass.h | 27 +++++++ .../convertPosConfidenceEllipse.h | 27 +++++++ .../convertPosFrontAx.h | 27 +++++++ .../convertPosLonCarr.h | 27 +++++++ .../convertPosPillar.h | 27 +++++++ .../convertPositionOfOccupants.h | 27 +++++++ .../convertPositionOfPillars.h | 27 +++++++ .../convertPositioningSolutionType.h | 27 +++++++ .../convertPostCrashSubCauseCode.h | 27 +++++++ .../convertProtectedCommunicationZone.h | 27 +++++++ .../convertProtectedCommunicationZonesRSU.h | 27 +++++++ .../convertProtectedZoneID.h | 27 +++++++ .../convertProtectedZoneRadius.h | 27 +++++++ .../convertProtectedZoneType.h | 27 +++++++ .../convertPtActivation.h | 27 +++++++ .../convertPtActivationData.h | 27 +++++++ .../convertPtActivationType.h | 27 +++++++ .../convertPublicTransportContainer.h | 27 +++++++ .../convertRSUContainerHighFrequency.h | 27 +++++++ .../convertReferencePosition.h | 27 +++++++ .../convertRelevanceDistance.h | 27 +++++++ .../convertRelevanceTrafficDirection.h | 27 +++++++ .../convertRequestResponseIndication.h | 27 +++++++ ...cueAndRecoveryWorkInProgressSubCauseCode.h | 27 +++++++ .../convertRescueContainer.h | 27 +++++++ .../convertRestrictedTypes.h | 27 +++++++ .../etsi_its_cam_conversion/convertRoadType.h | 27 +++++++ .../convertRoadWorksContainerBasic.h | 27 +++++++ .../convertRoadworksSubCauseCode.h | 27 +++++++ .../convertSafetyCarContainer.h | 27 +++++++ .../convertSemiAxisLength.h | 27 +++++++ .../convertSequenceNumber.h | 27 +++++++ .../convertSignalViolationSubCauseCode.h | 27 +++++++ .../convertSlowVehicleSubCauseCode.h | 27 +++++++ .../convertSpecialTransportContainer.h | 27 +++++++ .../convertSpecialTransportType.h | 27 +++++++ .../convertSpecialVehicleContainer.h | 27 +++++++ .../etsi_its_cam_conversion/convertSpeed.h | 27 +++++++ .../convertSpeedConfidence.h | 27 +++++++ .../convertSpeedLimit.h | 27 +++++++ .../convertSpeedValue.h | 27 +++++++ .../convertStationID.h | 27 +++++++ .../convertStationType.h | 27 +++++++ .../convertStationarySince.h | 27 +++++++ .../convertStationaryVehicleSubCauseCode.h | 27 +++++++ .../convertSteeringWheelAngle.h | 27 +++++++ .../convertSteeringWheelAngleConfidence.h | 27 +++++++ .../convertSteeringWheelAngleValue.h | 27 +++++++ .../convertSubCauseCodeType.h | 27 +++++++ .../convertTemperature.h | 27 +++++++ .../convertTimestampIts.h | 27 +++++++ .../etsi_its_cam_conversion/convertTraces.h | 27 +++++++ .../convertTrafficConditionSubCauseCode.h | 27 +++++++ .../convertTrafficRule.h | 27 +++++++ .../convertTransmissionInterval.h | 27 +++++++ .../convertTurningRadius.h | 27 +++++++ .../etsi_its_cam_conversion/convertVDS.h | 27 +++++++ .../convertValidityDuration.h | 27 +++++++ .../convertVehicleBreakdownSubCauseCode.h | 27 +++++++ .../convertVehicleIdentification.h | 27 +++++++ .../convertVehicleLength.h | 27 +++++++ ...convertVehicleLengthConfidenceIndication.h | 27 +++++++ .../convertVehicleLengthValue.h | 27 +++++++ .../convertVehicleMass.h | 27 +++++++ .../convertVehicleRole.h | 27 +++++++ .../convertVehicleWidth.h | 27 +++++++ .../convertVerticalAcceleration.h | 27 +++++++ .../convertVerticalAccelerationValue.h | 27 +++++++ .../convertWMInumber.h | 27 +++++++ .../convertWheelBaseVehicle.h | 27 +++++++ .../convertWrongWayDrivingSubCauseCode.h | 27 +++++++ .../etsi_its_cam_conversion/convertYawRate.h | 27 +++++++ .../convertYawRateConfidence.h | 27 +++++++ .../convertYawRateValue.h | 27 +++++++ .../convertAccelerationConfidence.h | 27 +++++++ .../convertAccelerationControl.h | 27 +++++++ .../convertAccidentSubCauseCode.h | 27 +++++++ .../convertActionID.h | 27 +++++++ ...erseWeatherConditionAdhesionSubCauseCode.h | 27 +++++++ ...itionExtremeWeatherConditionSubCauseCode.h | 27 +++++++ ...eatherConditionPrecipitationSubCauseCode.h | 27 +++++++ ...seWeatherConditionVisibilitySubCauseCode.h | 27 +++++++ .../convertAlacarteContainer.h | 27 +++++++ .../convertAltitude.h | 27 +++++++ .../convertAltitudeConfidence.h | 27 +++++++ .../convertAltitudeValue.h | 27 +++++++ .../convertCauseCode.h | 27 +++++++ .../convertCauseCodeType.h | 27 +++++++ .../convertCenDsrcTollingZone.h | 27 +++++++ .../convertCenDsrcTollingZoneID.h | 27 +++++++ .../convertClosedLanes.h | 27 +++++++ .../convertCollisionRiskSubCauseCode.h | 27 +++++++ .../convertCurvature.h | 27 +++++++ .../convertCurvatureCalculationMode.h | 27 +++++++ .../convertCurvatureConfidence.h | 27 +++++++ .../convertCurvatureValue.h | 27 +++++++ .../etsi_its_denm_conversion/convertDENM.h | 27 +++++++ .../convertDangerousEndOfQueueSubCauseCode.h | 27 +++++++ .../convertDangerousGoodsBasic.h | 27 +++++++ .../convertDangerousGoodsExtended.h | 27 +++++++ .../convertDangerousSituationSubCauseCode.h | 27 +++++++ ...tralizedEnvironmentalNotificationMessage.h | 27 +++++++ .../convertDeltaAltitude.h | 27 +++++++ .../convertDeltaLatitude.h | 27 +++++++ .../convertDeltaLongitude.h | 27 +++++++ .../convertDeltaReferencePosition.h | 27 +++++++ .../convertDigitalMap.h | 27 +++++++ .../convertDriveDirection.h | 27 +++++++ .../convertDrivingLaneStatus.h | 27 +++++++ .../convertEmbarkationStatus.h | 27 +++++++ .../convertEmergencyPriority.h | 27 +++++++ ...tEmergencyVehicleApproachingSubCauseCode.h | 27 +++++++ .../convertEnergyStorageType.h | 27 +++++++ .../convertEventHistory.h | 27 +++++++ .../convertEventPoint.h | 27 +++++++ .../convertExteriorLights.h | 27 +++++++ .../convertHardShoulderStatus.h | 27 +++++++ ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 27 +++++++ ...ardousLocationDangerousCurveSubCauseCode.h | 27 +++++++ ...ousLocationObstacleOnTheRoadSubCauseCode.h | 27 +++++++ ...dousLocationSurfaceConditionSubCauseCode.h | 27 +++++++ .../etsi_its_denm_conversion/convertHeading.h | 27 +++++++ .../convertHeadingConfidence.h | 27 +++++++ .../convertHeadingValue.h | 27 +++++++ .../convertHeightLonCarr.h | 27 +++++++ ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 27 +++++++ .../convertHumanProblemSubCauseCode.h | 27 +++++++ .../convertImpactReductionContainer.h | 27 +++++++ .../convertInformationQuality.h | 27 +++++++ .../convertItineraryPath.h | 27 +++++++ .../convertItsPduHeader.h | 27 +++++++ .../convertLanePosition.h | 27 +++++++ .../convertLateralAcceleration.h | 27 +++++++ .../convertLateralAccelerationValue.h | 27 +++++++ .../convertLatitude.h | 27 +++++++ .../convertLightBarSirenInUse.h | 27 +++++++ .../convertLocationContainer.h | 27 +++++++ .../convertLongitude.h | 27 +++++++ .../convertLongitudinalAcceleration.h | 27 +++++++ .../convertLongitudinalAccelerationValue.h | 27 +++++++ .../convertManagementContainer.h | 27 +++++++ .../convertNumberOfOccupants.h | 27 +++++++ .../convertOpeningDaysHours.h | 27 +++++++ .../convertPathDeltaTime.h | 27 +++++++ .../convertPathHistory.h | 27 +++++++ .../convertPathPoint.h | 27 +++++++ .../convertPerformanceClass.h | 27 +++++++ .../convertPhoneNumber.h | 27 +++++++ .../convertPosCentMass.h | 27 +++++++ .../convertPosConfidenceEllipse.h | 27 +++++++ .../convertPosFrontAx.h | 27 +++++++ .../convertPosLonCarr.h | 27 +++++++ .../convertPosPillar.h | 27 +++++++ .../convertPositionOfOccupants.h | 27 +++++++ .../convertPositionOfPillars.h | 27 +++++++ .../convertPositioningSolutionType.h | 27 +++++++ .../convertPostCrashSubCauseCode.h | 27 +++++++ .../convertProtectedCommunicationZone.h | 27 +++++++ .../convertProtectedCommunicationZonesRSU.h | 27 +++++++ .../convertProtectedZoneID.h | 27 +++++++ .../convertProtectedZoneRadius.h | 27 +++++++ .../convertProtectedZoneType.h | 27 +++++++ .../convertPtActivation.h | 27 +++++++ .../convertPtActivationData.h | 27 +++++++ .../convertPtActivationType.h | 27 +++++++ .../convertReferenceDenms.h | 27 +++++++ .../convertReferencePosition.h | 27 +++++++ .../convertRelevanceDistance.h | 27 +++++++ .../convertRelevanceTrafficDirection.h | 27 +++++++ .../convertRequestResponseIndication.h | 27 +++++++ ...cueAndRecoveryWorkInProgressSubCauseCode.h | 27 +++++++ .../convertRestrictedTypes.h | 27 +++++++ .../convertRoadType.h | 27 +++++++ .../convertRoadWorksContainerExtended.h | 27 +++++++ .../convertRoadworksSubCauseCode.h | 27 +++++++ .../convertSemiAxisLength.h | 27 +++++++ .../convertSequenceNumber.h | 27 +++++++ .../convertSignalViolationSubCauseCode.h | 27 +++++++ .../convertSituationContainer.h | 27 +++++++ .../convertSlowVehicleSubCauseCode.h | 27 +++++++ .../convertSpecialTransportType.h | 27 +++++++ .../etsi_its_denm_conversion/convertSpeed.h | 27 +++++++ .../convertSpeedConfidence.h | 27 +++++++ .../convertSpeedLimit.h | 27 +++++++ .../convertSpeedValue.h | 27 +++++++ .../convertStationID.h | 27 +++++++ .../convertStationType.h | 27 +++++++ .../convertStationarySince.h | 27 +++++++ .../convertStationaryVehicleContainer.h | 27 +++++++ .../convertStationaryVehicleSubCauseCode.h | 27 +++++++ .../convertSteeringWheelAngle.h | 27 +++++++ .../convertSteeringWheelAngleConfidence.h | 27 +++++++ .../convertSteeringWheelAngleValue.h | 27 +++++++ .../convertSubCauseCodeType.h | 27 +++++++ .../convertTemperature.h | 27 +++++++ .../convertTermination.h | 27 +++++++ .../convertTimestampIts.h | 27 +++++++ .../etsi_its_denm_conversion/convertTraces.h | 27 +++++++ .../convertTrafficConditionSubCauseCode.h | 27 +++++++ .../convertTrafficRule.h | 27 +++++++ .../convertTransmissionInterval.h | 27 +++++++ .../convertTurningRadius.h | 27 +++++++ .../etsi_its_denm_conversion/convertVDS.h | 27 +++++++ .../convertValidityDuration.h | 27 +++++++ .../convertVehicleBreakdownSubCauseCode.h | 27 +++++++ .../convertVehicleIdentification.h | 27 +++++++ .../convertVehicleLength.h | 27 +++++++ ...convertVehicleLengthConfidenceIndication.h | 27 +++++++ .../convertVehicleLengthValue.h | 27 +++++++ .../convertVehicleMass.h | 27 +++++++ .../convertVehicleRole.h | 27 +++++++ .../convertVehicleWidth.h | 27 +++++++ .../convertVerticalAcceleration.h | 27 +++++++ .../convertVerticalAccelerationValue.h | 27 +++++++ .../convertWMInumber.h | 27 +++++++ .../convertWheelBaseVehicle.h | 27 +++++++ .../convertWrongWayDrivingSubCauseCode.h | 27 +++++++ .../etsi_its_denm_conversion/convertYawRate.h | 27 +++++++ .../convertYawRateConfidence.h | 27 +++++++ .../convertYawRateValue.h | 27 +++++++ .../msg/AccelerationConfidence.msg | 27 +++++++ .../msg/AccelerationControl.msg | 27 +++++++ .../msg/AccidentSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/ActionID.msg | 27 +++++++ ...seWeatherConditionAdhesionSubCauseCode.msg | 27 +++++++ ...ionExtremeWeatherConditionSubCauseCode.msg | 27 +++++++ ...therConditionPrecipitationSubCauseCode.msg | 27 +++++++ ...WeatherConditionVisibilitySubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Altitude.msg | 27 +++++++ .../msg/AltitudeConfidence.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/AltitudeValue.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/BasicContainer.msg | 27 +++++++ .../BasicVehicleContainerHighFrequency.msg | 27 +++++++ .../msg/BasicVehicleContainerLowFrequency.msg | 27 +++++++ etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/CamParameters.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/CauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/CauseCodeType.msg | 27 +++++++ .../msg/CenDsrcTollingZone.msg | 27 +++++++ .../msg/CenDsrcTollingZoneID.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/ClosedLanes.msg | 27 +++++++ .../msg/CollisionRiskSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/CoopAwareness.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Curvature.msg | 27 +++++++ .../msg/CurvatureCalculationMode.msg | 27 +++++++ .../msg/CurvatureConfidence.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/CurvatureValue.msg | 27 +++++++ .../msg/DangerousEndOfQueueSubCauseCode.msg | 27 +++++++ .../msg/DangerousGoodsBasic.msg | 27 +++++++ .../msg/DangerousGoodsContainer.msg | 27 +++++++ .../msg/DangerousGoodsExtended.msg | 27 +++++++ .../msg/DangerousSituationSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/DeltaAltitude.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/DeltaLatitude.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/DeltaLongitude.msg | 27 +++++++ .../msg/DeltaReferencePosition.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/DigitalMap.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/DriveDirection.msg | 27 +++++++ .../msg/DrivingLaneStatus.msg | 27 +++++++ .../msg/EmbarkationStatus.msg | 27 +++++++ .../msg/EmergencyContainer.msg | 27 +++++++ .../msg/EmergencyPriority.msg | 27 +++++++ ...mergencyVehicleApproachingSubCauseCode.msg | 27 +++++++ .../msg/EnergyStorageType.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/EventHistory.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/EventPoint.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/ExteriorLights.msg | 27 +++++++ .../msg/GenerationDeltaTime.msg | 27 +++++++ .../msg/HardShoulderStatus.msg | 27 +++++++ ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 27 +++++++ ...dousLocationDangerousCurveSubCauseCode.msg | 27 +++++++ ...sLocationObstacleOnTheRoadSubCauseCode.msg | 27 +++++++ ...usLocationSurfaceConditionSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Heading.msg | 27 +++++++ .../msg/HeadingConfidence.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/HeadingValue.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/HeightLonCarr.msg | 27 +++++++ .../msg/HighFrequencyContainer.msg | 27 +++++++ .../HumanPresenceOnTheRoadSubCauseCode.msg | 27 +++++++ .../msg/HumanProblemSubCauseCode.msg | 27 +++++++ .../msg/InformationQuality.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/ItineraryPath.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/ItsPduHeader.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/LanePosition.msg | 27 +++++++ .../msg/LateralAcceleration.msg | 27 +++++++ .../msg/LateralAccelerationValue.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Latitude.msg | 27 +++++++ .../msg/LightBarSirenInUse.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Longitude.msg | 27 +++++++ .../msg/LongitudinalAcceleration.msg | 27 +++++++ .../msg/LongitudinalAccelerationValue.msg | 27 +++++++ .../msg/LowFrequencyContainer.msg | 27 +++++++ .../msg/NumberOfOccupants.msg | 27 +++++++ .../msg/OpeningDaysHours.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PathDeltaTime.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PathHistory.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PathPoint.msg | 27 +++++++ .../msg/PerformanceClass.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PhoneNumber.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PosCentMass.msg | 27 +++++++ .../msg/PosConfidenceEllipse.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PosFrontAx.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PosLonCarr.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PosPillar.msg | 27 +++++++ .../msg/PositionOfOccupants.msg | 27 +++++++ .../msg/PositionOfPillars.msg | 27 +++++++ .../msg/PositioningSolutionType.msg | 27 +++++++ .../msg/PostCrashSubCauseCode.msg | 27 +++++++ .../msg/ProtectedCommunicationZone.msg | 27 +++++++ .../msg/ProtectedCommunicationZonesRSU.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/ProtectedZoneID.msg | 27 +++++++ .../msg/ProtectedZoneRadius.msg | 27 +++++++ .../msg/ProtectedZoneType.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/PtActivation.msg | 27 +++++++ .../msg/PtActivationType.msg | 27 +++++++ .../msg/PublicTransportContainer.msg | 27 +++++++ .../msg/RSUContainerHighFrequency.msg | 27 +++++++ .../msg/ReferencePosition.msg | 27 +++++++ .../msg/RelevanceDistance.msg | 27 +++++++ .../msg/RelevanceTrafficDirection.msg | 27 +++++++ .../msg/RequestResponseIndication.msg | 27 +++++++ ...eAndRecoveryWorkInProgressSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/RescueContainer.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/RestrictedTypes.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/RoadType.msg | 27 +++++++ .../msg/RoadWorksContainerBasic.msg | 27 +++++++ .../msg/RoadworksSubCauseCode.msg | 27 +++++++ .../msg/SafetyCarContainer.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/SemiAxisLength.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/SequenceNumber.msg | 27 +++++++ .../msg/SignalViolationSubCauseCode.msg | 27 +++++++ .../msg/SlowVehicleSubCauseCode.msg | 27 +++++++ .../msg/SpecialTransportContainer.msg | 27 +++++++ .../msg/SpecialTransportType.msg | 27 +++++++ .../msg/SpecialVehicleContainer.msg | 27 +++++++ etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/SpeedConfidence.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/SpeedLimit.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/SpeedValue.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/StationID.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/StationType.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/StationarySince.msg | 27 +++++++ .../msg/StationaryVehicleSubCauseCode.msg | 27 +++++++ .../msg/SteeringWheelAngle.msg | 27 +++++++ .../msg/SteeringWheelAngleConfidence.msg | 27 +++++++ .../msg/SteeringWheelAngleValue.msg | 27 +++++++ .../msg/SubCauseCodeType.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Temperature.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/TimestampIts.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/Traces.msg | 27 +++++++ .../msg/TrafficConditionSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/TrafficRule.msg | 27 +++++++ .../msg/TransmissionInterval.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/TurningRadius.msg | 27 +++++++ etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg | 27 +++++++ .../msg/ValidityDuration.msg | 27 +++++++ .../msg/VehicleBreakdownSubCauseCode.msg | 27 +++++++ .../msg/VehicleIdentification.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/VehicleLength.msg | 27 +++++++ .../msg/VehicleLengthConfidenceIndication.msg | 27 +++++++ .../msg/VehicleLengthValue.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/VehicleMass.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/VehicleRole.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/VehicleWidth.msg | 27 +++++++ .../msg/VerticalAcceleration.msg | 27 +++++++ .../msg/VerticalAccelerationValue.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/WMInumber.msg | 27 +++++++ .../msg/WheelBaseVehicle.msg | 27 +++++++ .../msg/WrongWayDrivingSubCauseCode.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/YawRate.msg | 27 +++++++ .../msg/YawRateConfidence.msg | 27 +++++++ .../etsi_its_cam_msgs/msg/YawRateValue.msg | 27 +++++++ .../msg/AccelerationConfidence.msg | 27 +++++++ .../msg/AccelerationControl.msg | 27 +++++++ .../msg/AccidentSubCauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/ActionID.msg | 27 +++++++ ...seWeatherConditionAdhesionSubCauseCode.msg | 27 +++++++ ...ionExtremeWeatherConditionSubCauseCode.msg | 27 +++++++ ...therConditionPrecipitationSubCauseCode.msg | 27 +++++++ ...WeatherConditionVisibilitySubCauseCode.msg | 27 +++++++ .../msg/AlacarteContainer.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Altitude.msg | 27 +++++++ .../msg/AltitudeConfidence.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/AltitudeValue.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/CauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/CauseCodeType.msg | 27 +++++++ .../msg/CenDsrcTollingZone.msg | 27 +++++++ .../msg/CenDsrcTollingZoneID.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/ClosedLanes.msg | 27 +++++++ .../msg/CollisionRiskSubCauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Curvature.msg | 27 +++++++ .../msg/CurvatureCalculationMode.msg | 27 +++++++ .../msg/CurvatureConfidence.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/CurvatureValue.msg | 27 +++++++ etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg | 27 +++++++ .../msg/DangerousEndOfQueueSubCauseCode.msg | 27 +++++++ .../msg/DangerousGoodsBasic.msg | 27 +++++++ .../msg/DangerousGoodsExtended.msg | 27 +++++++ .../msg/DangerousSituationSubCauseCode.msg | 27 +++++++ ...alizedEnvironmentalNotificationMessage.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/DeltaAltitude.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/DeltaLatitude.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/DeltaLongitude.msg | 27 +++++++ .../msg/DeltaReferencePosition.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/DigitalMap.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/DriveDirection.msg | 27 +++++++ .../msg/DrivingLaneStatus.msg | 27 +++++++ .../msg/EmbarkationStatus.msg | 27 +++++++ .../msg/EmergencyPriority.msg | 27 +++++++ ...mergencyVehicleApproachingSubCauseCode.msg | 27 +++++++ .../msg/EnergyStorageType.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/EventHistory.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/EventPoint.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/ExteriorLights.msg | 27 +++++++ .../msg/HardShoulderStatus.msg | 27 +++++++ ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 27 +++++++ ...dousLocationDangerousCurveSubCauseCode.msg | 27 +++++++ ...sLocationObstacleOnTheRoadSubCauseCode.msg | 27 +++++++ ...usLocationSurfaceConditionSubCauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Heading.msg | 27 +++++++ .../msg/HeadingConfidence.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/HeadingValue.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/HeightLonCarr.msg | 27 +++++++ .../HumanPresenceOnTheRoadSubCauseCode.msg | 27 +++++++ .../msg/HumanProblemSubCauseCode.msg | 27 +++++++ .../msg/ImpactReductionContainer.msg | 27 +++++++ .../msg/InformationQuality.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/ItineraryPath.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/ItsPduHeader.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/LanePosition.msg | 27 +++++++ .../msg/LateralAcceleration.msg | 27 +++++++ .../msg/LateralAccelerationValue.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Latitude.msg | 27 +++++++ .../msg/LightBarSirenInUse.msg | 27 +++++++ .../msg/LocationContainer.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Longitude.msg | 27 +++++++ .../msg/LongitudinalAcceleration.msg | 27 +++++++ .../msg/LongitudinalAccelerationValue.msg | 27 +++++++ .../msg/ManagementContainer.msg | 27 +++++++ .../msg/NumberOfOccupants.msg | 27 +++++++ .../msg/OpeningDaysHours.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PathDeltaTime.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PathHistory.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PathPoint.msg | 27 +++++++ .../msg/PerformanceClass.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PhoneNumber.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PosCentMass.msg | 27 +++++++ .../msg/PosConfidenceEllipse.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PosFrontAx.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PosLonCarr.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PosPillar.msg | 27 +++++++ .../msg/PositionOfOccupants.msg | 27 +++++++ .../msg/PositionOfPillars.msg | 27 +++++++ .../msg/PositioningSolutionType.msg | 27 +++++++ .../msg/PostCrashSubCauseCode.msg | 27 +++++++ .../msg/ProtectedCommunicationZone.msg | 27 +++++++ .../msg/ProtectedCommunicationZonesRSU.msg | 27 +++++++ .../msg/ProtectedZoneID.msg | 27 +++++++ .../msg/ProtectedZoneRadius.msg | 27 +++++++ .../msg/ProtectedZoneType.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/PtActivation.msg | 27 +++++++ .../msg/PtActivationType.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/ReferenceDenms.msg | 27 +++++++ .../msg/ReferencePosition.msg | 27 +++++++ .../msg/RelevanceDistance.msg | 27 +++++++ .../msg/RelevanceTrafficDirection.msg | 27 +++++++ .../msg/RequestResponseIndication.msg | 27 +++++++ ...eAndRecoveryWorkInProgressSubCauseCode.msg | 27 +++++++ .../msg/RestrictedTypes.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/RoadType.msg | 27 +++++++ .../msg/RoadWorksContainerExtended.msg | 27 +++++++ .../msg/RoadworksSubCauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/SemiAxisLength.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/SequenceNumber.msg | 27 +++++++ .../msg/SignalViolationSubCauseCode.msg | 27 +++++++ .../msg/SituationContainer.msg | 27 +++++++ .../msg/SlowVehicleSubCauseCode.msg | 27 +++++++ .../msg/SpecialTransportType.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Speed.msg | 27 +++++++ .../msg/SpeedConfidence.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/SpeedLimit.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/SpeedValue.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/StationID.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/StationType.msg | 27 +++++++ .../msg/StationarySince.msg | 27 +++++++ .../msg/StationaryVehicleContainer.msg | 27 +++++++ .../msg/StationaryVehicleSubCauseCode.msg | 27 +++++++ .../msg/SteeringWheelAngle.msg | 27 +++++++ .../msg/SteeringWheelAngleConfidence.msg | 27 +++++++ .../msg/SteeringWheelAngleValue.msg | 27 +++++++ .../msg/SubCauseCodeType.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Temperature.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Termination.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/TimestampIts.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/Traces.msg | 27 +++++++ .../msg/TrafficConditionSubCauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/TrafficRule.msg | 27 +++++++ .../msg/TransmissionInterval.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/TurningRadius.msg | 27 +++++++ etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg | 27 +++++++ .../msg/ValidityDuration.msg | 27 +++++++ .../msg/VehicleBreakdownSubCauseCode.msg | 27 +++++++ .../msg/VehicleIdentification.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/VehicleLength.msg | 27 +++++++ .../msg/VehicleLengthConfidenceIndication.msg | 27 +++++++ .../msg/VehicleLengthValue.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/VehicleMass.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/VehicleRole.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/VehicleWidth.msg | 27 +++++++ .../msg/VerticalAcceleration.msg | 27 +++++++ .../msg/VerticalAccelerationValue.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/WMInumber.msg | 27 +++++++ .../msg/WheelBaseVehicle.msg | 27 +++++++ .../msg/WrongWayDrivingSubCauseCode.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/YawRate.msg | 27 +++++++ .../msg/YawRateConfidence.msg | 27 +++++++ .../etsi_its_denm_msgs/msg/YawRateValue.msg | 27 +++++++ .../docker/rgen/src/conversion/template.rs | 30 ++++++- .../codegen/docker/rgen/src/msgs/template.rs | 80 ++++++++++++++----- 598 files changed, 16179 insertions(+), 23 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h index 5c1960beb..7b030b752 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AccelerationConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h index c8c3b2fc0..9302ae5d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING AccelerationControl diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h index 15a251cff..27eff85a6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AccidentSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index f38c0fe50..cec2204d6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ActionID diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index de3a68f59..9e485879b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionAdhesionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 919ca03c1..4f6e63b95 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index b7d4a2f58..de6f3d23a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionPrecipitationSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index 4c7d86d27..fb7a3bc2b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionVisibilitySubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index f8cece502..f61a38ec1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Altitude diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h index fb35b2a71..c6bc772fc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED AltitudeConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h index f07dd495e..eb00d72eb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AltitudeValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index 6a7daf9ff..5e6b1ed14 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE BasicContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index b29c26189..41d225fb5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE BasicVehicleContainerHighFrequency diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index 9e75547dd..fcd810c89 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE BasicVehicleContainerLowFrequency diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index bab31d2f7..e4761658c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CAM // The root data frame for cooperative awareness messages diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index 3eaa415ae..8f9d41621 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CamParameters diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h index b2551d9b5..d74d4ccab 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h index fc379e214..25907cb56 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER CauseCodeType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index 175ad1ea3..b24c52f2a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CenDsrcTollingZone diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h index 2a183937b..3c683ca71 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// TYPEALIAS CenDsrcTollingZoneID diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h index 1975333eb..656b774d1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ClosedLanes diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h index d7c4ab0ba..16a6a376b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER CollisionRiskSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h index f56b4a066..cebee1234 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CoopAwareness diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index eff4e3b81..38661d85c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Curvature diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h index 8076507a4..28b587f94 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED CurvatureCalculationMode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h index d3ef7cbc3..10ba44b3d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED CurvatureConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h index 40e166b7c..4db3ea455 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER CurvatureValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h index a9c2dd61e..92156d78c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DangerousEndOfQueueSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h index 2f9bfb5ab..c74c9031b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED DangerousGoodsBasic diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h index 40bc035d6..e2a1e5490 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DangerousGoodsContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index 81d6f388c..d05102754 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DangerousGoodsExtended diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h index 298754886..bf3f1e578 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DangerousSituationSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h index 49a817b02..5232bd2fe 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DeltaAltitude diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h index a2ccb471f..24158960f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DeltaLatitude diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h index 835cf3d6e..f4283eb46 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DeltaLongitude diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index f0f809bd1..1f193cdf9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DeltaReferencePosition diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h index 9df37e996..15f387ae3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF DigitalMap diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h index ea7006322..63979f9ae 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED DriveDirection diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h index 4451f1dbf..bcdc23013 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING DrivingLaneStatus diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h index 7e639372d..3983d8430 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BOOLEAN EmbarkationStatus diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index 10f3eee7c..cc7ce1df0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE EmergencyContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h index 1f6dbfa79..6e69d1bbd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING EmergencyPriority diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 9062e0fc3..046d1a30c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER EmergencyVehicleApproachingSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h index 3d3f10c1a..e1ed497e2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING EnergyStorageType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index 2ef1c6bcf..faab4577c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF EventHistory diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index ebc2ba8c5..8a2715274 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE EventPoint diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h index 6f22eafed..575ae5277 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING ExteriorLights diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h index 0ac2031af..9eb24d457 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER GenerationDeltaTime diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h index acee43990..2344246d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED HardShoulderStatus diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 0eca0d2aa..57011e4d5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index e57593598..7132ef1ee 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationDangerousCurveSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index b8b58e45c..dcec4c5f8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 014e5752a..42d6b4953 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationSurfaceConditionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index 4d44b337b..1ba8f3432 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Heading diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h index 98289f46f..41fe903af 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HeadingConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h index 95400c78b..83c390fd7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HeadingValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h index fdbaa2d03..7ce7f767e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HeightLonCarr diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h index bca1c1c56..07b06c21c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// CHOICE HighFrequencyContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index 0efea238c..ba486b78b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HumanPresenceOnTheRoadSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h index 406ae6724..10b7f0e98 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HumanProblemSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h index c2bc19d8f..48ebe0f7e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER InformationQuality diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h index e17895882..e10e262b1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF ItineraryPath diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h index 3b915c33d..1546f7625 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ItsPduHeader diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h index 17cdd4bc0..610209b25 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER LanePosition diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index 6246ed087..ecaee5dcb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE LateralAcceleration diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h index 9af6bfc11..df6214dc7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER LateralAccelerationValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h index 8301894e4..fd012b405 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER Latitude diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h index e02a2fb05..39427bf6d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING LightBarSirenInUse diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h index 449b745ec..e459673dd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER Longitude diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h index 93006fdfc..2988eacdd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE LongitudinalAcceleration diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h index 365e97b0d..aef7329e9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER LongitudinalAccelerationValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h index facb053a1..ac9a953e6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// CHOICE LowFrequencyContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h index 2505897b9..16c479fda 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER NumberOfOccupants diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h index 21d5da81c..896b2dfe3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// UTF8String OpeningDaysHours diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h index 41ff920fe..91757738d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PathDeltaTime diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h index 22133d938..6a152a468 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF PathHistory diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index 83c96ecc4..30403c61e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PathPoint diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h index 13b7a8e18..8d846643f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PerformanceClass diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h index 9594e2dea..181ff03c1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// NumericString PhoneNumber diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h index d5fcbf1d3..7355ca2fa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosCentMass diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index 5bbe13e17..7321483bf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PosConfidenceEllipse diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h index 186238114..5323f1d1d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosFrontAx diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h index 4c5c6512f..7fb9b07d0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosLonCarr diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h index b5dc50feb..08073d045 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosPillar diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h index 56a2019ce..f11feb925 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING PositionOfOccupants diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index d3f91c7b7..67344e0bf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF PositionOfPillars diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h index 29851247d..8e105535a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED PositioningSolutionType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h index daa1db40e..5a683ba5b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PostCrashSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index c6e5e49a3..fb6d4f47c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ProtectedCommunicationZone diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index 9e0ad6935..c03d39f8c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF ProtectedCommunicationZonesRSU diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h index 132294e25..c611e7cc4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER ProtectedZoneID diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h index 9dec6d7d3..b9f35617d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER ProtectedZoneRadius diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h index 5b3d0d18a..91273f25f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED ProtectedZoneType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index 34f110383..782394911 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PtActivation diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h index 63c38ab89..747efe100 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// OCTET-STRING PtActivationData diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h index eb99048d8..6e89e9230 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PtActivationType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index 0da0e3113..f2cb3fa96 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PublicTransportContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h index bb58ec061..b9a03bb1c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE RSUContainerHighFrequency diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index 5be307ff3..763f96dec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ReferencePosition diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h index c57c6feaa..94905185a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RelevanceDistance diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h index 79075d231..c9ca4e9ac 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RelevanceTrafficDirection diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h index 379a7a378..2ef8acc52 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RequestResponseIndication diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index fb8343d69..708f2ef75 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER RescueAndRecoveryWorkInProgressSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h index 4cfb1991b..887b58e3d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE RescueContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index 49b59aa48..c339b6461 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF RestrictedTypes diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h index 93885f497..2fda3dbf6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RoadType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index a23182f36..d97381053 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE RoadWorksContainerBasic diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h index 196c06866..0013668cf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER RoadworksSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index c031f52c4..95759f363 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE SafetyCarContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h index 4862cc6da..d2aa1b1ef 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SemiAxisLength diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h index 8412c3361..6f629a380 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SequenceNumber diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h index a455af8cb..75b0d6b31 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SignalViolationSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h index 03644fb8d..d023ca480 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SlowVehicleSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h index 2187f4e09..09e5c2124 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE SpecialTransportContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h index 49d709836..a48408e6f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING SpecialTransportType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index 5d6242e21..121c0b96d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// CHOICE SpecialVehicleContainer diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index ca3d31f2d..b815908ec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Speed diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h index 74981ab2c..60cf49e9c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SpeedConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h index 7413358a0..64017e72d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SpeedLimit diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h index 3bd0d34cf..3392b338e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SpeedValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h index 833df3d70..4e267a466 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER StationID diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h index 61480bfe0..7807999e8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER StationType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h index 4f4847ffd..9bc7ff50a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED StationarySince diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h index e8c9ab611..6f2dbe531 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER StationaryVehicleSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index d765f952c..910737ea9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE SteeringWheelAngle diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h index 89c463006..7fe66af04 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SteeringWheelAngleConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h index 7e7a04cdb..155de1eff 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SteeringWheelAngleValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h index 45277cdbc..691e51eac 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SubCauseCodeType diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h index f0f02aeff..381676751 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER Temperature diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h index dd39d6854..37e5f64b7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TimestampIts diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index f810e66f4..c95eb4a23 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF Traces diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h index f2f551f51..d1e5be3df 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TrafficConditionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h index 35fceafc2..5ac173b6f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED TrafficRule diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h index e4fb251e2..ff33d1bc7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TransmissionInterval diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h index 79692be4d..1c023aa0a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TurningRadius diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h index 5c3378e1f..59171475a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// IA5String VDS diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h index 5070bf909..79527f32d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER ValidityDuration diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h index 9c66a2e63..3bd117634 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleBreakdownSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index 33921da9d..3e044b8cf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE VehicleIdentification diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index 4ed75c9c2..49e5b5717 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE VehicleLength diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h index 31e375abb..d8d6aa84e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED VehicleLengthConfidenceIndication diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h index 5ee3b2c0a..cb30ef81b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleLengthValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h index e97468791..7f0793218 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleMass diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h index 43242a4fd..8beeb695c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED VehicleRole diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h index cff25ebc9..889655cd1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleWidth diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index b1a1b2d52..84e432f70 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE VerticalAcceleration diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h index 790489e15..2f4bad71a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VerticalAccelerationValue diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h index 9e5728015..fc9b63ab8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// IA5String WMInumber diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h index 0f23c2019..abfcdf582 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER WheelBaseVehicle diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h index 09b08f9a1..ea2f7164c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER WrongWayDrivingSubCauseCode diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index bdb592288..8999ef7aa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE YawRate diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h index da6677eab..e247da1ec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED YawRateConfidence diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h index c200ba4f3..fdc50241c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER YawRateValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h index a1d641c4b..901e832b7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AccelerationConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h index 8035158d4..7890f3fc8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING AccelerationControl diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h index eb5b7166f..87989b902 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AccidentSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index 354dc4662..4fd28f1f2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ActionID diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index a12f95aff..4e3b48d04 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionAdhesionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 40504bd83..092e98fc0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index f098f06dc..ae36ae449 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionPrecipitationSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index d721b092f..94bfc6ef6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AdverseWeatherConditionVisibilitySubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index c5d89d47d..816a4ece2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE AlacarteContainer diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index a9fc51a42..794c648bb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Altitude diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h index 8866ed53f..072bd869c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED AltitudeConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h index 2d7fbb00c..1ca200eec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER AltitudeValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index c5f14d0e8..99bb2054f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h index 1d86fec34..ecb2a446b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER CauseCodeType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 1f2ae2fb6..4ecad1ee7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE CenDsrcTollingZone diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h index 04cc68677..f3bdc5d57 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// TYPEALIAS CenDsrcTollingZoneID diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index c287b1575..19d0b04dd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ClosedLanes diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h index db868261e..024c39ba0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER CollisionRiskSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index 413cfd35a..f4ff874a5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Curvature diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h index fa48affe0..15a6c9bdb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED CurvatureCalculationMode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h index 21cba7145..fb8d9e348 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED CurvatureConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h index 423d4465a..c7443b024 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER CurvatureValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h index 97b3f8d64..fd852655b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DENM diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h index a3cb2e180..2a2879ae4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DangerousEndOfQueueSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h index 74c112437..dc0ae4d92 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED DangerousGoodsBasic diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index ff4dafb68..a7a5fc68d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DangerousGoodsExtended diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h index e02ace1b0..aa11170c2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DangerousSituationSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index 174e1def8..36b3d10f8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DecentralizedEnvironmentalNotificationMessage diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h index 4289a1ad1..1f2e84942 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DeltaAltitude diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h index b2be76d9f..b26897317 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DeltaLatitude diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h index b32f71083..99316b425 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER DeltaLongitude diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index 5a459ba6e..f9b540e25 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE DeltaReferencePosition diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h index be3c0b1eb..a8d4ce809 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF DigitalMap diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h index d96877308..31ff44f0b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED DriveDirection diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h index 31847df68..3faee3a8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING DrivingLaneStatus diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h index ce8bcd728..21ae660a1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BOOLEAN EmbarkationStatus diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h index 3e1740f23..f620e0d5c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING EmergencyPriority diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 40b21ac10..046cfd300 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER EmergencyVehicleApproachingSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h index 78bb25f92..5ca43ee7c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING EnergyStorageType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h index d07c8a47c..a454c3935 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF EventHistory diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index b15402196..0f85c124b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE EventPoint diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h index fd073fdec..f0d5d886f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING ExteriorLights diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h index 49e07d73d..ded15fd94 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED HardShoulderStatus diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index aacddcd87..bfec27339 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index 1e5e15b50..2913c2de3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationDangerousCurveSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index ff6cbe3a5..f1647b5b0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 83c9c8fc7..ee028a10b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HazardousLocationSurfaceConditionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index 9b6422494..506b5cdf0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Heading diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h index 19374a60d..803e12b8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HeadingConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h index 2590e1196..96f24ed3c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HeadingValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h index b75b1e29c..8f989eec2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HeightLonCarr diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index 6b0fa421b..18efa87bc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HumanPresenceOnTheRoadSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h index 22f3764da..a718b2f22 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER HumanProblemSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index 8e5b2eb5c..e18c9f739 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ImpactReductionContainer diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h index 444a6bbe4..b1dc672a9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER InformationQuality diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index 957758cce..952e35f8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF ItineraryPath diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index 21e550b9d..9f649ef92 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ItsPduHeader diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h index b13c33742..3f9544da7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER LanePosition diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h index 6a2235fbc..c474de0e4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE LateralAcceleration diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h index 186bc1e24..ae8b3a7d7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER LateralAccelerationValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h index 607841873..3bde306af 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER Latitude diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h index 4a4fe5a49..7efcb8da8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING LightBarSirenInUse diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index 82ca0a858..613c02eaf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE LocationContainer diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h index 2c5a00086..3851a606b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER Longitude diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index a6866e221..1817552c3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE LongitudinalAcceleration diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h index 9162a1393..4d3fd466f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER LongitudinalAccelerationValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index 66230914c..72ef6b524 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ManagementContainer diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h index cf653ff3c..de7a171b4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER NumberOfOccupants diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h index 6277e9f14..1ae6b276b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// UTF8String OpeningDaysHours diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h index 4dced4b2b..9eabf099f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PathDeltaTime diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h index 88652a850..a218246e3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF PathHistory diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index be4921fa9..0415c1981 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PathPoint diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h index 9dfc6a278..92ecf0a33 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PerformanceClass diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h index 767730c15..f68edf9cc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// NumericString PhoneNumber diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h index 90c766f11..ae82f1a25 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosCentMass diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 3cb06f59c..b2a40c790 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PosConfidenceEllipse diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h index 2d75b7325..46034f602 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosFrontAx diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h index 618ab3703..d2d9e9337 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosLonCarr diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h index e651cf425..e7036d39f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PosPillar diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h index d752fa263..76b61688b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING PositionOfOccupants diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h index 7ba6314ab..e6bd20dcf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF PositionOfPillars diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h index 5d2b84f0d..ce9fc6881 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED PositioningSolutionType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h index 063d0f40a..51f4f905d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PostCrashSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index ef459c648..1b5a2c30b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ProtectedCommunicationZone diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h index f0c8319d7..16f4ac4d6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF ProtectedCommunicationZonesRSU diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h index 8360f9dde..de7cc6f58 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER ProtectedZoneID diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h index 2e3dfa506..165d46ba0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER ProtectedZoneRadius diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h index 261cfb6e4..f9994d328 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED ProtectedZoneType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index 27a6141b1..bf7b38560 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE PtActivation diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h index 42c352f5b..c1cbc351e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// OCTET-STRING PtActivationData diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h index 864d7fe34..33670b88e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER PtActivationType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index dc482fd2f..b53e438ea 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF ReferenceDenms diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index faa4c47d1..4cfa8e350 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE ReferencePosition diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h index 85c0b8352..8ef44bd15 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RelevanceDistance diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h index 9b644ce36..16e64825a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RelevanceTrafficDirection diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h index 0873dc736..522e1584e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RequestResponseIndication diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index 453af4c6e..4eca8b072 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER RescueAndRecoveryWorkInProgressSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h index 7bd6d7a39..0823bf132 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF RestrictedTypes diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h index aaa981d50..9ba9199de 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED RoadType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index e65fb8277..efded5c7f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE RoadWorksContainerExtended diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h index 80f4b3185..158b4abf2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER RoadworksSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h index c6090fee3..ce7670dd5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SemiAxisLength diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h index 0baf8b5e6..6a4d528f7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SequenceNumber diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h index f3da90978..5e8a4b1ee 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SignalViolationSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index a92397833..ca6cf3868 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE SituationContainer diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h index a8f84e92c..d5ec3203b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SlowVehicleSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h index 22757aa89..03cef559e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// BIT-STRING SpecialTransportType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index 0dcdd50b5..8266a1e48 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE Speed diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h index 46fe8fa2a..a02d4f4fc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SpeedConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h index 4f854bdaf..533927a6f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SpeedLimit diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h index 10467171f..7b2286540 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SpeedValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h index 42aafcbaf..91cccf075 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER StationID diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h index 7227c4e59..83cd3c3c5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER StationType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h index 136527453..a8d818959 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED StationarySince diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 9b0f0bb1e..006516075 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE StationaryVehicleContainer diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h index 816bb1909..c839d4cd7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER StationaryVehicleSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index 4e7c4543a..86a1e1e24 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE SteeringWheelAngle diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h index ce30e3734..a81e299b7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SteeringWheelAngleConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h index 9d2ff11da..497fc9709 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SteeringWheelAngleValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h index b86ab2bea..274a5ff94 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER SubCauseCodeType diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h index 542222b5d..fa3c0a635 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER Temperature diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h index 4d11e8772..e229bb851 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED Termination diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h index 77b8052a9..53765cb1a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TimestampIts diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 1126b25e8..7eadf0db7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE-OF Traces diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h index 3d4a228bd..cb9a641c1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TrafficConditionSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h index 1edf243a9..65613fa59 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED TrafficRule diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h index 1ed85aaec..c59b0b62a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TransmissionInterval diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h index bdb223ee8..a5f3e0449 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER TurningRadius diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h index 5804229c1..b9a24ee6c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// IA5String VDS diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h index 15b2f7cbb..dfe95cb8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER ValidityDuration diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h index eeb1089c1..7c348ba80 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleBreakdownSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index 6ab983ebe..7a66815d4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE VehicleIdentification diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index 821a114a3..f74d0c0fe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE VehicleLength diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h index 14ed9a8a8..3e6662652 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED VehicleLengthConfidenceIndication diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h index aec4c2df7..5f56f9e3d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleLengthValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h index 65901d25f..2464c99fa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleMass diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h index 9bd66ddfb..6d5576192 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED VehicleRole diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h index 04361bc52..4b1810d72 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VehicleWidth diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index 0e35794b4..de677823e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE VerticalAcceleration diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h index 7a773ba24..4eb52b0e7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER VerticalAccelerationValue diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h index b469faf90..7921d88d6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// IA5String WMInumber diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h index f06439c6e..4c00ede7e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER WheelBaseVehicle diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h index e974ab54e..1a4e9ab81 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER WrongWayDrivingSubCauseCode diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h index a1965ceaf..185c0e637 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// SEQUENCE YawRate diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h index d93f80306..4391e50ec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// ENUMERATED YawRateConfidence diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h index f065249e0..0583dbb92 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h @@ -1,3 +1,30 @@ +/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + //// INTEGER YawRateValue diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg index 9865b14b3..39c273bbd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AccelerationConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg index 4a7f9d5c5..2c4c19149 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING AccelerationControl uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg index 796d1b8b9..24d083f87 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AccidentSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg index 20cb30ac9..eb29a0f07 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ActionID StationID originating_station_id diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 8dfc404d6..662392eec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionAdhesionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 5e8c226b8..15cbe797a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index b71e00a5b..e1aa73660 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 2914f7b84..102915f9b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionVisibilitySubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg index ee0b01eb4..594d9d37c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Altitude AltitudeValue altitude_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg index e6081a967..7c3a95c22 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED AltitudeConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg index db7c77a3d..5fb1d7c33 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AltitudeValue int32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg index c716cd243..b324717c8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE BasicContainer .extensible StationType station_type diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg index b5ac28ce2..013210e53 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE BasicVehicleContainerHighFrequency Heading heading diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg index a1d377741..426397172 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE BasicVehicleContainerLowFrequency VehicleRole vehicle_role diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg index 1af66c4c2..f5230f84c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CAM # The root data frame for cooperative awareness messages diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg index d87f12a96..b6b4461ae 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CamParameters .extensible BasicContainer basic_container diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg index e3fdccaff..973c89781 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CauseCode .extensible CauseCodeType cause_code diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg index 172a0fc12..f873754cc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER CauseCodeType uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg index 449a28242..a05df3837 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CenDsrcTollingZone .extensible Latitude protected_zone_latitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg index efb20a09e..6fc8d1f81 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## TYPE-ALIAS CenDsrcTollingZoneID ProtectedZoneID value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg index aec88d388..77134bbcd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ClosedLanes .extensible bool innerhard_shoulder_status_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg index f3afe70d0..df3412e0c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER CollisionRiskSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg index a6304da16..4b7c2596d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CoopAwareness GenerationDeltaTime generation_delta_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg index 21f001b6a..1786b4977 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Curvature CurvatureValue curvature_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg index d76cf7cdd..b9e8e49d3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED CurvatureCalculationMode .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg index 17bbbf4de..b36c4ea4d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED CurvatureConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg index da3928552..9d1974f26 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER CurvatureValue int16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index b6d9d0329..beea5c8a1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DangerousEndOfQueueSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg index df3611bb6..8a9140b26 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED DangerousGoodsBasic uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg index a04ff7a10..0f5c1e091 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DangerousGoodsContainer DangerousGoodsBasic dangerous_goods_basic diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg index 577cba69f..4a38b0f84 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DangerousGoodsExtended .extensible DangerousGoodsBasic dangerous_goods_type diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg index 5c1089ce4..ef126f527 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DangerousSituationSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg index ed6cdfa42..5ee397cad 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DeltaAltitude int16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg index 3aaa64597..561ca3b33 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DeltaLatitude int32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg index 1c61c7b4d..0b4a95b64 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DeltaLongitude int32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg index ce78e8e7d..31a9f06dc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DeltaReferencePosition DeltaLatitude delta_latitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg index ef631d52d..569cfd6d6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF DigitalMap ReferencePosition[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg index 581ffa6dc..2d1c95e2a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED DriveDirection uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg index 228db1255..220968a79 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING DrivingLaneStatus uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg index d529b3842..b52eb16db 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BOOLEAN EmbarkationStatus bool value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg index c3405eac6..4e140cbe1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE EmergencyContainer LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg index b80ba12a6..c81f118e7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING EmergencyPriority uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 73bff4f9a..88df9871d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER EmergencyVehicleApproachingSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg index 26e57dfde..591c76718 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING EnergyStorageType uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg index be3e6559c..d48877dd8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF EventHistory EventPoint[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg index bf18a2813..1643fe007 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE EventPoint DeltaReferencePosition event_position diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg index 957ddc36b..e865cb77d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING ExteriorLights uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg index 979d501c1..06ef6b756 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER GenerationDeltaTime uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg index 460f5aede..e19c27a02 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED HardShoulderStatus uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 8257e6ff6..ddbc580f8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index fd2bb3c4c..4d6e18d8c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationDangerousCurveSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index fa3691914..7b7221621 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 4e8c792aa..e29146cd5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationSurfaceConditionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg index 68df9e493..95c48bc5f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Heading HeadingValue heading_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg index 4cb626ae0..c8e97c562 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HeadingConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg index 7164cd19b..4ead96652 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HeadingValue uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg index 6152a4e51..4041aa8cd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HeightLonCarr uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg index a6d55d8b0..69473ba68 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## CHOICE HighFrequencyContainer .extensible uint8 choice diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 72163a10c..317a4b8e0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HumanPresenceOnTheRoadSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg index bf40a01d8..e5866377f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HumanProblemSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg index 5af7ec4f4..7ac459b0f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER InformationQuality uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg index 15459d1e4..41b54a3c8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF ItineraryPath ReferencePosition[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg index 50098612e..e0e95b0c5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ItsPduHeader uint8 protocol_version diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg index c2ea265d2..2729a0deb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER LanePosition int8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg index b75736df9..a8afa582f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE LateralAcceleration LateralAccelerationValue lateral_acceleration_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg index fa022135b..db9cf92b6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER LateralAccelerationValue int16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg index c5be6a7af..0b95abe96 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER Latitude int32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg index 30bb5e2a1..464b1bb86 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING LightBarSirenInUse uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg index bddc707df..9f0bbac8b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER Longitude int32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg index a56e0c176..501b57fba 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE LongitudinalAcceleration LongitudinalAccelerationValue longitudinal_acceleration_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg index 8b438016e..90a6d1c80 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER LongitudinalAccelerationValue int16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg index 18e45a1bd..549b35262 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## CHOICE LowFrequencyContainer .extensible uint8 choice diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg index 1431e2612..cba00ac08 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER NumberOfOccupants uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg index 843b5354d..ea4ca5882 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## Utf8String OpeningDaysHours string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg index d0ecaba0f..e07b00515 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PathDeltaTime int64 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg index 1b3d17250..6ffb371be 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF PathHistory PathPoint[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg index a3e508126..3a66f5c33 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PathPoint DeltaReferencePosition path_position diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg index 9d69f56cd..84e9690d6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PerformanceClass uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg index 2d89e9df9..87c284302 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## NumericString PhoneNumber string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg index cfc9cd9bc..a4e5238ff 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosCentMass uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg index 0077d220d..ebf822654 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PosConfidenceEllipse SemiAxisLength semi_major_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg index 13a451247..bf9032811 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosFrontAx uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg index 43154206d..9b6643818 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosLonCarr uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg index b476f8996..dea1c83a8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosPillar uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg index 10c70ae2d..5320b5167 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING PositionOfOccupants uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg index 02b14d0df..015f83995 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF PositionOfPillars PosPillar[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg index 8cfa98a57..aad52eeb7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED PositioningSolutionType .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg index 291b9969e..624da3885 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PostCrashSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg index 335f5fcc2..13bdb1cce 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ProtectedCommunicationZone .extensible ProtectedZoneType protected_zone_type diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg index 3e68a4b85..b5e61b046 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF ProtectedCommunicationZonesRSU ProtectedCommunicationZone[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg index 8ad38e935..6597bca31 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER ProtectedZoneID uint32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg index e5fce0ff6..2c685a0a7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER ProtectedZoneRadius int64 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg index 277c99b9a..812c608d7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED ProtectedZoneType .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg index b067e6f81..ce76306de 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PtActivation PtActivationType pt_activation_type diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg index dbf87a49d..889884086 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PtActivationType uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg index 93fd6639a..2b75db37f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PublicTransportContainer EmbarkationStatus embarkation_status diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg index 62fc3d858..3d14fdfec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE RSUContainerHighFrequency .extensible bool protected_communication_zones_rsu_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg index 2e15eb7bd..dd647f7d2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ReferencePosition Latitude latitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg index 52210df13..23fe60283 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RelevanceDistance uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg index 1b942c3ed..867fa1853 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RelevanceTrafficDirection uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg index 45e45c756..856dfe2fb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RequestResponseIndication uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index bacf1a7ea..360516e4f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg index 544ac9987..0801c8305 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE RescueContainer LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg index 61e48f1e6..46ce145ca 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF RestrictedTypes StationType[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg index dd2e542e7..7ab57d5c2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RoadType uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg index fbd474704..851fe39e3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE RoadWorksContainerBasic bool roadworks_sub_cause_code_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg index 20057cc6a..1c70e3429 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER RoadworksSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg index bc38f220d..3081c1d65 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE SafetyCarContainer LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg index 083e860ab..00570648c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SemiAxisLength uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg index 5171880d2..46de8a045 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SequenceNumber uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg index a7d121127..85cd4c570 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SignalViolationSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg index 131897657..b2851a5dc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SlowVehicleSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg index 50b0ac923..663ac4291 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE SpecialTransportContainer SpecialTransportType special_transport_type diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg index ca8a3f72a..11895303b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING SpecialTransportType uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg index 38c8797bc..4a98f8e8a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## CHOICE SpecialVehicleContainer .extensible uint8 choice diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg index cac581f03..23aef070f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Speed SpeedValue speed_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg index 34a84c0fc..0b8c93e95 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SpeedConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg index 3a459e7ce..e71840559 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SpeedLimit uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg index e18097a0f..f61585f55 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SpeedValue uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg index f49d34323..8b688adc3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER StationID uint32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg index e91775578..5674dcae4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER StationType uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg index 80b7c9660..1e851253c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED StationarySince uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg index c48785887..adf013ce3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER StationaryVehicleSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg index 76e9ef597..7d033b9dd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE SteeringWheelAngle SteeringWheelAngleValue steering_wheel_angle_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg index dbd12e458..836d42c04 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SteeringWheelAngleConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg index 9b04cdf9f..afb11301f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SteeringWheelAngleValue int16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg index b08a83005..76b818aae 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SubCauseCodeType uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg index f2a497ef5..2259fe2cf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER Temperature int8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg index 342fcf26b..6ebee0fb7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TimestampIts uint64 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg index 479157e9d..45e61c7a9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF Traces PathHistory[] array diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg index c060c7ebc..3bf2c7572 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TrafficConditionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg index e138ac055..381da7c71 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED TrafficRule .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg index e505df9b5..76153c55f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TransmissionInterval uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg index 11de9132c..7ca5596d8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TurningRadius uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg index b08a5c238..2a19a755b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## Ia5String VDS string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg index d11827ef1..806532404 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER ValidityDuration uint32 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg index ef3d2d1c6..79ed4c0b0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleBreakdownSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg index 1b7b25c07..73c04c673 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE VehicleIdentification .extensible bool w_m_inumber_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg index 543253116..513a60967 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE VehicleLength VehicleLengthValue vehicle_length_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg index 5cd4611f7..b74b2519a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED VehicleLengthConfidenceIndication uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg index 2c2bc6e87..7e43bcf2c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleLengthValue uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg index 949dc93b2..c8e936d57 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleMass uint16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg index dee2e6e66..d3a9a2c74 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED VehicleRole uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg index 0ff4d5cee..575bb2893 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleWidth uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg index c6927a06c..78515df4c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE VerticalAcceleration VerticalAccelerationValue vertical_acceleration_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg index 2267e732c..20e71ad81 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VerticalAccelerationValue int16 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg index fef01bdbf..4f15b48b3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## Ia5String WMInumber string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg index 4a9feb773..77d9730b3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER WheelBaseVehicle uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg index 4ee06efd1..73b00caaf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER WrongWayDrivingSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg index 69e8f08eb..64e05f9a2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE YawRate YawRateValue yaw_rate_value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg index 72f3c0bf8..397121d65 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED YawRateConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg index 8c0e228b7..2a8dbc3e5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER YawRateValue int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg index 9865b14b3..39c273bbd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AccelerationConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg index 4a7f9d5c5..2c4c19149 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING AccelerationControl uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg index 796d1b8b9..24d083f87 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AccidentSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg index 20cb30ac9..eb29a0f07 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ActionID StationID originating_station_id diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 8dfc404d6..662392eec 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionAdhesionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 5e8c226b8..15cbe797a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index b71e00a5b..e1aa73660 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 2914f7b84..102915f9b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AdverseWeatherConditionVisibilitySubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg index 7ad3eb900..3f09db98f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE AlacarteContainer .extensible bool lane_position_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg index ee0b01eb4..594d9d37c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Altitude AltitudeValue altitude_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg index e6081a967..7c3a95c22 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED AltitudeConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg index db7c77a3d..5fb1d7c33 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER AltitudeValue int32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg index e3fdccaff..973c89781 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CauseCode .extensible CauseCodeType cause_code diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg index 172a0fc12..f873754cc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER CauseCodeType uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg index 449a28242..a05df3837 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE CenDsrcTollingZone .extensible Latitude protected_zone_latitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg index efb20a09e..6fc8d1f81 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## TYPE-ALIAS CenDsrcTollingZoneID ProtectedZoneID value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg index aec88d388..77134bbcd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ClosedLanes .extensible bool innerhard_shoulder_status_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg index f3afe70d0..df3412e0c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER CollisionRiskSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg index 21f001b6a..1786b4977 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Curvature CurvatureValue curvature_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg index d76cf7cdd..b9e8e49d3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED CurvatureCalculationMode .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg index 17bbbf4de..b36c4ea4d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED CurvatureConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg index da3928552..9d1974f26 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER CurvatureValue int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg index d5d1fd36f..0087d1183 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DENM ItsPduHeader header diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index b6d9d0329..beea5c8a1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DangerousEndOfQueueSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg index df3611bb6..8a9140b26 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED DangerousGoodsBasic uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg index 577cba69f..4a38b0f84 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DangerousGoodsExtended .extensible DangerousGoodsBasic dangerous_goods_type diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg index 5c1089ce4..ef126f527 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DangerousSituationSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg index 347475286..f8f9ed8bd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DecentralizedEnvironmentalNotificationMessage ManagementContainer management diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg index ed6cdfa42..5ee397cad 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DeltaAltitude int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg index 3aaa64597..561ca3b33 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DeltaLatitude int32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg index 1c61c7b4d..0b4a95b64 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER DeltaLongitude int32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg index ce78e8e7d..31a9f06dc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE DeltaReferencePosition DeltaLatitude delta_latitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg index ef631d52d..569cfd6d6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF DigitalMap ReferencePosition[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg index 581ffa6dc..2d1c95e2a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED DriveDirection uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg index 228db1255..220968a79 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING DrivingLaneStatus uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg index d529b3842..b52eb16db 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BOOLEAN EmbarkationStatus bool value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg index b80ba12a6..c81f118e7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING EmergencyPriority uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 73bff4f9a..88df9871d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER EmergencyVehicleApproachingSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg index 26e57dfde..591c76718 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING EnergyStorageType uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg index be3e6559c..d48877dd8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF EventHistory EventPoint[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg index bf18a2813..1643fe007 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE EventPoint DeltaReferencePosition event_position diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg index 957ddc36b..e865cb77d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING ExteriorLights uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg index 460f5aede..e19c27a02 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED HardShoulderStatus uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 8257e6ff6..ddbc580f8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index fd2bb3c4c..4d6e18d8c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationDangerousCurveSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index fa3691914..7b7221621 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 4e8c792aa..e29146cd5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HazardousLocationSurfaceConditionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg index 68df9e493..95c48bc5f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Heading HeadingValue heading_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg index 4cb626ae0..c8e97c562 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HeadingConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg index 7164cd19b..4ead96652 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HeadingValue uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg index 6152a4e51..4041aa8cd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HeightLonCarr uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 72163a10c..317a4b8e0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HumanPresenceOnTheRoadSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg index bf40a01d8..e5866377f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER HumanProblemSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg index e7ca74fcd..e5c34ebc5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ImpactReductionContainer HeightLonCarr height_lon_carr_left diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg index 5af7ec4f4..7ac459b0f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER InformationQuality uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg index 15459d1e4..41b54a3c8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF ItineraryPath ReferencePosition[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg index 50098612e..e0e95b0c5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ItsPduHeader uint8 protocol_version diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg index c2ea265d2..2729a0deb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER LanePosition int8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg index b75736df9..a8afa582f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE LateralAcceleration LateralAccelerationValue lateral_acceleration_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg index fa022135b..db9cf92b6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER LateralAccelerationValue int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg index c5be6a7af..0b95abe96 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER Latitude int32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg index 30bb5e2a1..464b1bb86 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING LightBarSirenInUse uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg index b8fc171f6..360c3f2f2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE LocationContainer .extensible bool event_speed_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg index bddc707df..9f0bbac8b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER Longitude int32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg index a56e0c176..501b57fba 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE LongitudinalAcceleration LongitudinalAccelerationValue longitudinal_acceleration_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg index 8b438016e..90a6d1c80 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER LongitudinalAccelerationValue int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg index df0684afa..6fb21c3fb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ManagementContainer .extensible ActionID action_id diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg index 1431e2612..cba00ac08 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER NumberOfOccupants uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg index 843b5354d..ea4ca5882 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## Utf8String OpeningDaysHours string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg index d0ecaba0f..e07b00515 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PathDeltaTime int64 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg index 1b3d17250..6ffb371be 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF PathHistory PathPoint[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg index a3e508126..3a66f5c33 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PathPoint DeltaReferencePosition path_position diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg index 9d69f56cd..84e9690d6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PerformanceClass uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg index 2d89e9df9..87c284302 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## NumericString PhoneNumber string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg index cfc9cd9bc..a4e5238ff 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosCentMass uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg index 0077d220d..ebf822654 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PosConfidenceEllipse SemiAxisLength semi_major_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg index 13a451247..bf9032811 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosFrontAx uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg index 43154206d..9b6643818 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosLonCarr uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg index b476f8996..dea1c83a8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PosPillar uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg index 10c70ae2d..5320b5167 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING PositionOfOccupants uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg index 02b14d0df..015f83995 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF PositionOfPillars PosPillar[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg index 8cfa98a57..aad52eeb7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED PositioningSolutionType .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg index 291b9969e..624da3885 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PostCrashSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg index 335f5fcc2..13bdb1cce 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ProtectedCommunicationZone .extensible ProtectedZoneType protected_zone_type diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg index 3e68a4b85..b5e61b046 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF ProtectedCommunicationZonesRSU ProtectedCommunicationZone[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg index 8ad38e935..6597bca31 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER ProtectedZoneID uint32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg index e5fce0ff6..2c685a0a7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER ProtectedZoneRadius int64 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg index 277c99b9a..812c608d7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED ProtectedZoneType .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg index b067e6f81..ce76306de 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE PtActivation PtActivationType pt_activation_type diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg index dbf87a49d..889884086 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER PtActivationType uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg index b78dcf946..7c2b9b329 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF ReferenceDenms ActionID[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg index 2e15eb7bd..dd647f7d2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE ReferencePosition Latitude latitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg index 52210df13..23fe60283 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RelevanceDistance uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg index 1b942c3ed..867fa1853 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RelevanceTrafficDirection uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg index 45e45c756..856dfe2fb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RequestResponseIndication uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index bacf1a7ea..360516e4f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg index 61e48f1e6..46ce145ca 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF RestrictedTypes StationType[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg index dd2e542e7..7ab57d5c2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED RoadType uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg index d498b926f..e99f6f67e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE RoadWorksContainerExtended bool light_bar_siren_in_use_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg index 20057cc6a..1c70e3429 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER RoadworksSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg index 083e860ab..00570648c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SemiAxisLength uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg index 5171880d2..46de8a045 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SequenceNumber uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg index a7d121127..85cd4c570 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SignalViolationSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg index 4f6c47bcb..002cb9eec 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE SituationContainer .extensible InformationQuality information_quality diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg index 131897657..b2851a5dc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SlowVehicleSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg index ca8a3f72a..11895303b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## BIT-STRING SpecialTransportType uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg index cac581f03..23aef070f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE Speed SpeedValue speed_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg index 34a84c0fc..0b8c93e95 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SpeedConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg index 3a459e7ce..e71840559 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SpeedLimit uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg index e18097a0f..f61585f55 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SpeedValue uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg index f49d34323..8b688adc3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER StationID uint32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg index e91775578..5674dcae4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER StationType uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg index 80b7c9660..1e851253c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED StationarySince uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg index 9377af699..5d69a6db5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE StationaryVehicleContainer bool stationary_since_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg index c48785887..adf013ce3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER StationaryVehicleSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg index 76e9ef597..7d033b9dd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE SteeringWheelAngle SteeringWheelAngleValue steering_wheel_angle_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg index dbd12e458..836d42c04 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SteeringWheelAngleConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg index 9b04cdf9f..afb11301f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SteeringWheelAngleValue int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg index b08a83005..76b818aae 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER SubCauseCodeType uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg index f2a497ef5..2259fe2cf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER Temperature int8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg index a2b23ce05..04b1c59ce 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED Termination uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg index 342fcf26b..6ebee0fb7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TimestampIts uint64 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg index 479157e9d..45e61c7a9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE-OF Traces PathHistory[] array diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg index c060c7ebc..3bf2c7572 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TrafficConditionSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg index e138ac055..381da7c71 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED TrafficRule .extensible uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg index e505df9b5..76153c55f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TransmissionInterval uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg index 11de9132c..7ca5596d8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER TurningRadius uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg index b08a5c238..2a19a755b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## Ia5String VDS string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg index d11827ef1..806532404 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER ValidityDuration uint32 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg index ef3d2d1c6..79ed4c0b0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleBreakdownSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg index 1b7b25c07..73c04c673 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE VehicleIdentification .extensible bool w_m_inumber_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg index 543253116..513a60967 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE VehicleLength VehicleLengthValue vehicle_length_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg index 5cd4611f7..b74b2519a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED VehicleLengthConfidenceIndication uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg index 2c2bc6e87..7e43bcf2c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleLengthValue uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg index 949dc93b2..c8e936d57 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleMass uint16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg index dee2e6e66..d3a9a2c74 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED VehicleRole uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg index 0ff4d5cee..575bb2893 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VehicleWidth uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg index c6927a06c..78515df4c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE VerticalAcceleration VerticalAccelerationValue vertical_acceleration_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg index 2267e732c..20e71ad81 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER VerticalAccelerationValue int16 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg index fef01bdbf..4f15b48b3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## Ia5String WMInumber string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg index 4a9feb773..77d9730b3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER WheelBaseVehicle uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg index 4ee06efd1..73b00caaf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER WrongWayDrivingSubCauseCode uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg index 69e8f08eb..64e05f9a2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## SEQUENCE YawRate YawRateValue yaw_rate_value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg index 72f3c0bf8..397121d65 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## ENUMERATED YawRateConfidence uint8 value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg index 8c0e228b7..2a8dbc3e5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg @@ -1,3 +1,30 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + ## INTEGER YawRateValue int16 value diff --git a/utils/codegen/docker/rgen/src/conversion/template.rs b/utils/codegen/docker/rgen/src/conversion/template.rs index d96f016ab..1b4eda1bf 100644 --- a/utils/codegen/docker/rgen/src/conversion/template.rs +++ b/utils/codegen/docker/rgen/src/conversion/template.rs @@ -4,7 +4,35 @@ use crate::conversion::ConversionOptions; use std::collections::HashMap; -const CONVERSION_TEMPLATE: &str = r#"//// {asn1_type} {name} +const CONVERSION_TEMPLATE: &str = +r#"/** ============================================================================ +MIT License + +Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +============================================================================= */ + +// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- + +//// {asn1_type} {name} {comments} #pragma once diff --git a/utils/codegen/docker/rgen/src/msgs/template.rs b/utils/codegen/docker/rgen/src/msgs/template.rs index 14283a48d..b48ab1de9 100644 --- a/utils/codegen/docker/rgen/src/msgs/template.rs +++ b/utils/codegen/docker/rgen/src/msgs/template.rs @@ -1,26 +1,62 @@ +const MSG_TEMPLATE: &str = +r#"# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + +{definition}"#; + +macro_rules! licensed { + ($definition:expr) => { + MSG_TEMPLATE.replace("{definition}", $definition) + }; +} + pub fn typealias_template(comments: &str, name: &str, alias: &str, annotations: &str) -> String { - format!( + licensed!(&format!( "## TYPE-ALIAS {name}\n\ {comments}\n\ {alias} value\n\ {annotations}" - ) + )) } pub fn integer_value_template(comments: &str, name: &str, vtype: &str, value: &str) -> String { - format!( + licensed!(&format!( "## INTEGER-DEF {name}\n\ {comments}\n\ {vtype} {name} = {value}" - ) + )) } pub fn lazy_static_value_template(comments: &str, name: &str, vtype: &str, value: &str) -> String { - format!( + licensed!(&format!( "## VALUE {name}\n\ {comments}\n\ {vtype} value = {value}" - ) + )) } pub fn integer_template( @@ -33,13 +69,13 @@ pub fn integer_template( let typed_dvalues = dvalues .replace("{type}", &integer_type) .replace("{prefix}", ""); - format!( + licensed!(&format!( "## INTEGER {name}\n\ {comments}\n\ {integer_type} value\n\n\ {constraints}\n\n\ {typed_dvalues}" - ) + )) } pub fn generalized_time_template(_comments: &str, _name: &str, _annotations: &str) -> String { @@ -54,14 +90,14 @@ pub fn bit_string_template(comments: &str, name: &str, constraints: &str, dvalue let typed_dvalues = dvalues .replace("{type}", "uint8") .replace("{prefix}", "BIT_INDEX_"); - format!( + licensed!(&format!( "## BIT-STRING {name}\n\ {comments}\n\ uint8[] value\n\ uint8 bits_unused\n\ {constraints}\n\n\ {typed_dvalues}" - ) + )) } pub fn octet_string_template(comments: &str, name: &str, annotations: &str) -> String { @@ -79,21 +115,21 @@ pub fn char_string_template( string_type: &str, annotations: &str, ) -> String { - format!( + licensed!(&format!( "## {string_type} {name}\n\ {comments}\n\ string value\n\ {annotations}" - ) + )) } pub fn boolean_template(comments: &str, name: &str, annotations: &str) -> String { - format!( + licensed!(&format!( "## BOOLEAN {name}\n\ {comments}\n\ bool value\n\ {annotations}" - ) + )) } pub fn primitive_value_template( @@ -133,13 +169,13 @@ pub fn enumerated_template( enum_members: &str, annotations: &str, ) -> String { - format!( + licensed!(&format!( "## ENUMERATED {name} {extensible}\n\ {comments}\n\ uint8 value\n\ {enum_members}\n\ {annotations}" - ) + )) } pub fn _sequence_or_set_value_template( @@ -162,7 +198,7 @@ pub fn sequence_or_set_template( default_methods: &str, class_fields: &str, ) -> String { - format!( + licensed!(&format!( "## SEQUENCE {name} {extensible}\n\ {comments}\n\ {members}\n\ @@ -171,7 +207,7 @@ pub fn sequence_or_set_template( {default_methods}\n\ {class_fields}", nested_members.join("\n") - ) + )) } pub fn sequence_or_set_of_template( @@ -182,12 +218,12 @@ pub fn sequence_or_set_of_template( member_type: &str, constraints: &str, ) -> String { - format!( + licensed!(&format!( "## SEQUENCE-OF {name}\n\ {comments}\n\ {member_type}[] array\n\ {constraints}" - ) + )) } pub fn choice_value_template( @@ -218,7 +254,7 @@ pub fn choice_template( nested_options: Vec, annotations: &str, ) -> String { - format!( + licensed!(&format!( "## CHOICE {name} {extensible}\n\ {comments}\n\ uint8 choice\n\n\ @@ -226,5 +262,5 @@ pub fn choice_template( {}\n\ {annotations}", nested_options.join("\n") - ) + )) } From 403f05ac8ab92c00ded09dae6c0f4d2cbd51e8e6 Mon Sep 17 00:00:00 2001 From: v0-e Date: Mon, 3 Jun 2024 22:09:51 +0100 Subject: [PATCH 11/22] refactor: Codegen dir structure --- .github/workflows/codegen.yml | 10 +++++----- .gitlab-ci.codegen.yml | 8 ++++---- .vscode/launch.json | 16 ++++++++-------- README.md | 4 ++-- .../{ => codegen-py}/asn1CodeGenerationUtils.py | 0 .../{ => codegen-py}/asn1ToConversionHeader.py | 0 utils/codegen/{ => codegen-py}/asn1ToRosMsg.py | 0 .../templates/RosMessageType.msg.jinja2 | 0 .../templates/convertChoiceType.h.jinja2 | 0 .../templates/convertCustomType.h.jinja2 | 0 .../templates/convertEnumeratedType.h.jinja2 | 0 .../templates/convertPrimitiveType.h.jinja2 | 0 .../templates/convertSequenceOfType.h.jinja2 | 0 .../templates/convertSequenceType.h.jinja2 | 0 .../asn1ToConversionHeader.py} | 0 .../asn1ToRosMsg.py} | 0 .../{ => codegen-rust}/docker/rgen.Dockerfile | 0 .../{docker => codegen-rust}/rgen/.gitignore | 0 .../{docker => codegen-rust}/rgen/Cargo.lock | 0 .../{docker => codegen-rust}/rgen/Cargo.toml | 0 .../{docker => codegen-rust}/rgen/README.md | 0 .../rgen/src/common/mod.rs | 0 .../rgen/src/conversion/bin.rs | 0 .../rgen/src/conversion/builder.rs | 0 .../rgen/src/conversion/mod.rs | 0 .../rgen/src/conversion/template.rs | 0 .../rgen/src/conversion/utils.rs | 0 .../{docker => codegen-rust}/rgen/src/lib.rs | 0 .../rgen/src/msgs/bin.rs | 0 .../rgen/src/msgs/builder.rs | 0 .../rgen/src/msgs/mod.rs | 0 .../rgen/src/msgs/template.rs | 0 .../rgen/src/msgs/utils.rs | 0 .../rgen/tests/conversion.rs | 0 .../{docker => codegen-rust}/rgen/tests/msgs.rs | 0 .../{docker => codegen-rust}/rgen/tests/utils.rs | 0 36 files changed, 19 insertions(+), 19 deletions(-) rename utils/codegen/{ => codegen-py}/asn1CodeGenerationUtils.py (100%) rename utils/codegen/{ => codegen-py}/asn1ToConversionHeader.py (100%) rename utils/codegen/{ => codegen-py}/asn1ToRosMsg.py (100%) rename utils/codegen/{ => codegen-py}/templates/RosMessageType.msg.jinja2 (100%) rename utils/codegen/{ => codegen-py}/templates/convertChoiceType.h.jinja2 (100%) rename utils/codegen/{ => codegen-py}/templates/convertCustomType.h.jinja2 (100%) rename utils/codegen/{ => codegen-py}/templates/convertEnumeratedType.h.jinja2 (100%) rename utils/codegen/{ => codegen-py}/templates/convertPrimitiveType.h.jinja2 (100%) rename utils/codegen/{ => codegen-py}/templates/convertSequenceOfType.h.jinja2 (100%) rename utils/codegen/{ => codegen-py}/templates/convertSequenceType.h.jinja2 (100%) rename utils/codegen/{asn1ToConversionHeader-rgen.py => codegen-rust/asn1ToConversionHeader.py} (100%) rename utils/codegen/{asn1ToRosMsg-rgen.py => codegen-rust/asn1ToRosMsg.py} (100%) rename utils/codegen/{ => codegen-rust}/docker/rgen.Dockerfile (100%) rename utils/codegen/{docker => codegen-rust}/rgen/.gitignore (100%) rename utils/codegen/{docker => codegen-rust}/rgen/Cargo.lock (100%) rename utils/codegen/{docker => codegen-rust}/rgen/Cargo.toml (100%) rename utils/codegen/{docker => codegen-rust}/rgen/README.md (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/common/mod.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/conversion/bin.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/conversion/builder.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/conversion/mod.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/conversion/template.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/conversion/utils.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/lib.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/msgs/bin.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/msgs/builder.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/msgs/mod.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/msgs/template.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/src/msgs/utils.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/tests/conversion.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/tests/msgs.rs (100%) rename utils/codegen/{docker => codegen-rust}/rgen/tests/utils.rs (100%) diff --git a/.github/workflows/codegen.yml b/.github/workflows/codegen.yml index 571b97045..671c11564 100644 --- a/.github/workflows/codegen.yml +++ b/.github/workflows/codegen.yml @@ -52,9 +52,9 @@ jobs: matrix: include: - message: cam - script: ./utils/codegen/asn1ToRosMsg.py asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn asn1/raw/cam_en302637_2/cdd/ITS-Container.asn -o etsi_its_msgs/etsi_its_cam_msgs/msg + script: ./utils/codegen/codegen-py/asn1ToRosMsg.py asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn asn1/raw/cam_en302637_2/cdd/ITS-Container.asn -o etsi_its_msgs/etsi_its_cam_msgs/msg - message: denm - script: ./utils/codegen/asn1ToRosMsg.py asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn asn1/raw/denm_en302637_3/cdd/ITS-Container.asn -o etsi_its_msgs/etsi_its_denm_msgs/msg + script: ./utils/codegen/codegen-py/asn1ToRosMsg.py asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn asn1/raw/denm_en302637_3/cdd/ITS-Container.asn -o etsi_its_msgs/etsi_its_denm_msgs/msg steps: - name: Checkout code @@ -84,9 +84,9 @@ jobs: matrix: include: - message: cam - script: ./utils/codegen/asn1ToConversionHeader.py asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn asn1/raw/cam_en302637_2/cdd/ITS-Container.asn -t cam -o etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion + script: ./utils/codegen/codegen-py/asn1ToConversionHeader.py asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn asn1/raw/cam_en302637_2/cdd/ITS-Container.asn -t cam -o etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion - message: denm - script: ./utils/codegen/asn1ToConversionHeader.py asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn asn1/raw/denm_en302637_3/cdd/ITS-Container.asn -t denm -o etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion + script: ./utils/codegen/codegen-py/asn1ToConversionHeader.py asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn asn1/raw/denm_en302637_3/cdd/ITS-Container.asn -t denm -o etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion steps: - name: Checkout code @@ -107,4 +107,4 @@ jobs: echo "Code generation script resulted in changes to the repository" git diff exit 1 - fi \ No newline at end of file + fi diff --git a/.gitlab-ci.codegen.yml b/.gitlab-ci.codegen.yml index 53de74e3d..a4f95d299 100644 --- a/.gitlab-ci.codegen.yml +++ b/.gitlab-ci.codegen.yml @@ -62,7 +62,7 @@ etsi_its_cam_msgs: needs: [] script: - > - ./utils/codegen/asn1ToRosMsg.py + ./utils/codegen/codegen-py/asn1ToRosMsg.py asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn asn1/raw/cam_en302637_2/cdd/ITS-Container.asn -o etsi_its_msgs/etsi_its_cam_msgs/msg @@ -73,7 +73,7 @@ etsi_its_denm_msgs: needs: [] script: - > - ./utils/codegen/asn1ToRosMsg.py + ./utils/codegen/codegen-py/asn1ToRosMsg.py asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn asn1/raw/denm_en302637_3/cdd/ITS-Container.asn -o etsi_its_msgs/etsi_its_denm_msgs/msg @@ -85,7 +85,7 @@ etsi_its_cam_conversion: needs: [] script: - > - ./utils/codegen/asn1ToConversionHeader.py + ./utils/codegen/codegen-py/asn1ToConversionHeader.py asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn asn1/raw/cam_en302637_2/cdd/ITS-Container.asn -t cam @@ -97,7 +97,7 @@ etsi_its_denm_conversion: needs: [] script: - > - ./utils/codegen/asn1ToConversionHeader.py + ./utils/codegen/codegen-py/asn1ToConversionHeader.py asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn asn1/raw/denm_en302637_3/cdd/ITS-Container.asn -t denm diff --git a/.vscode/launch.json b/.vscode/launch.json index 6c25ad89e..7def9956e 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -34,7 +34,7 @@ "name": "CAM asn1ToRosMsg", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToRosMsg.py", + "program": "utils/codegen/codegen-py/asn1ToRosMsg.py", "args": [ "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", @@ -48,7 +48,7 @@ "name": "DENM asn1ToRosMsg", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToRosMsg.py", + "program": "utils/codegen/codegen-py/asn1ToRosMsg.py", "args": [ "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", @@ -62,7 +62,7 @@ "name": "CAM asn1ToConversionHeader", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToConversionHeader.py", + "program": "utils/codegen/codegen-py/asn1ToConversionHeader.py", "args": [ "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", @@ -77,7 +77,7 @@ "name": "DENM asn1ToConversionHeader", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToConversionHeader.py", + "program": "utils/codegen/codegen-py/asn1ToConversionHeader.py", "args": [ "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", @@ -92,7 +92,7 @@ "name": "CAM asn1ToRosMsg (rgen)", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToRosMsg-rgen.py", + "program": "utils/codegen/codegen-rust/asn1ToRosMsg.py", "args": [ "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", @@ -106,7 +106,7 @@ "name": "DENM asn1ToRosMsg (rgen)", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToRosMsg-rgen.py", + "program": "utils/codegen/codegen-rust/asn1ToRosMsg.py", "args": [ "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", @@ -120,7 +120,7 @@ "name": "CAM asn1ToConversionHeader (rgen)", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToConversionHeader-rgen.py", + "program": "utils/codegen/codegen-rust/asn1ToConversionHeader.py", "args": [ "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", @@ -135,7 +135,7 @@ "name": "DENM asn1ToConversionHeader (rgen)", "type": "python", "request": "launch", - "program": "utils/codegen/asn1ToConversionHeader-rgen.py", + "program": "utils/codegen/codegen-rust/asn1ToConversionHeader.py", "args": [ "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", diff --git a/README.md b/README.md index 0e0807083..99afbae1b 100644 --- a/README.md +++ b/README.md @@ -94,7 +94,7 @@ The ROS message files are auto-generated based on the [ASN.1 definitions](https: ```bash # etsi_its_messages$ -./utils/codegen/asn1ToRosMsg.py \ +./utils/codegen/codegen-py/asn1ToRosMsg.py \ asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn \ asn1/raw/cam_en302637_2/cdd/ITS-Container.asn \ -o etsi_its_msgs/etsi_its_cam_msgs/msg @@ -181,7 +181,7 @@ The C++ conversion functions are auto-generated based on the [ASN.1 definitions] ```bash # etsi_its_messages$ -./utils/codegen/asn1ToConversionHeader.py \ +./utils/codegen/codegen-py/asn1ToConversionHeader.py \ asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn \ asn1/raw/cam_en302637_2/cdd/ITS-Container.asn \ -t cam \ diff --git a/utils/codegen/asn1CodeGenerationUtils.py b/utils/codegen/codegen-py/asn1CodeGenerationUtils.py similarity index 100% rename from utils/codegen/asn1CodeGenerationUtils.py rename to utils/codegen/codegen-py/asn1CodeGenerationUtils.py diff --git a/utils/codegen/asn1ToConversionHeader.py b/utils/codegen/codegen-py/asn1ToConversionHeader.py similarity index 100% rename from utils/codegen/asn1ToConversionHeader.py rename to utils/codegen/codegen-py/asn1ToConversionHeader.py diff --git a/utils/codegen/asn1ToRosMsg.py b/utils/codegen/codegen-py/asn1ToRosMsg.py similarity index 100% rename from utils/codegen/asn1ToRosMsg.py rename to utils/codegen/codegen-py/asn1ToRosMsg.py diff --git a/utils/codegen/templates/RosMessageType.msg.jinja2 b/utils/codegen/codegen-py/templates/RosMessageType.msg.jinja2 similarity index 100% rename from utils/codegen/templates/RosMessageType.msg.jinja2 rename to utils/codegen/codegen-py/templates/RosMessageType.msg.jinja2 diff --git a/utils/codegen/templates/convertChoiceType.h.jinja2 b/utils/codegen/codegen-py/templates/convertChoiceType.h.jinja2 similarity index 100% rename from utils/codegen/templates/convertChoiceType.h.jinja2 rename to utils/codegen/codegen-py/templates/convertChoiceType.h.jinja2 diff --git a/utils/codegen/templates/convertCustomType.h.jinja2 b/utils/codegen/codegen-py/templates/convertCustomType.h.jinja2 similarity index 100% rename from utils/codegen/templates/convertCustomType.h.jinja2 rename to utils/codegen/codegen-py/templates/convertCustomType.h.jinja2 diff --git a/utils/codegen/templates/convertEnumeratedType.h.jinja2 b/utils/codegen/codegen-py/templates/convertEnumeratedType.h.jinja2 similarity index 100% rename from utils/codegen/templates/convertEnumeratedType.h.jinja2 rename to utils/codegen/codegen-py/templates/convertEnumeratedType.h.jinja2 diff --git a/utils/codegen/templates/convertPrimitiveType.h.jinja2 b/utils/codegen/codegen-py/templates/convertPrimitiveType.h.jinja2 similarity index 100% rename from utils/codegen/templates/convertPrimitiveType.h.jinja2 rename to utils/codegen/codegen-py/templates/convertPrimitiveType.h.jinja2 diff --git a/utils/codegen/templates/convertSequenceOfType.h.jinja2 b/utils/codegen/codegen-py/templates/convertSequenceOfType.h.jinja2 similarity index 100% rename from utils/codegen/templates/convertSequenceOfType.h.jinja2 rename to utils/codegen/codegen-py/templates/convertSequenceOfType.h.jinja2 diff --git a/utils/codegen/templates/convertSequenceType.h.jinja2 b/utils/codegen/codegen-py/templates/convertSequenceType.h.jinja2 similarity index 100% rename from utils/codegen/templates/convertSequenceType.h.jinja2 rename to utils/codegen/codegen-py/templates/convertSequenceType.h.jinja2 diff --git a/utils/codegen/asn1ToConversionHeader-rgen.py b/utils/codegen/codegen-rust/asn1ToConversionHeader.py similarity index 100% rename from utils/codegen/asn1ToConversionHeader-rgen.py rename to utils/codegen/codegen-rust/asn1ToConversionHeader.py diff --git a/utils/codegen/asn1ToRosMsg-rgen.py b/utils/codegen/codegen-rust/asn1ToRosMsg.py similarity index 100% rename from utils/codegen/asn1ToRosMsg-rgen.py rename to utils/codegen/codegen-rust/asn1ToRosMsg.py diff --git a/utils/codegen/docker/rgen.Dockerfile b/utils/codegen/codegen-rust/docker/rgen.Dockerfile similarity index 100% rename from utils/codegen/docker/rgen.Dockerfile rename to utils/codegen/codegen-rust/docker/rgen.Dockerfile diff --git a/utils/codegen/docker/rgen/.gitignore b/utils/codegen/codegen-rust/rgen/.gitignore similarity index 100% rename from utils/codegen/docker/rgen/.gitignore rename to utils/codegen/codegen-rust/rgen/.gitignore diff --git a/utils/codegen/docker/rgen/Cargo.lock b/utils/codegen/codegen-rust/rgen/Cargo.lock similarity index 100% rename from utils/codegen/docker/rgen/Cargo.lock rename to utils/codegen/codegen-rust/rgen/Cargo.lock diff --git a/utils/codegen/docker/rgen/Cargo.toml b/utils/codegen/codegen-rust/rgen/Cargo.toml similarity index 100% rename from utils/codegen/docker/rgen/Cargo.toml rename to utils/codegen/codegen-rust/rgen/Cargo.toml diff --git a/utils/codegen/docker/rgen/README.md b/utils/codegen/codegen-rust/rgen/README.md similarity index 100% rename from utils/codegen/docker/rgen/README.md rename to utils/codegen/codegen-rust/rgen/README.md diff --git a/utils/codegen/docker/rgen/src/common/mod.rs b/utils/codegen/codegen-rust/rgen/src/common/mod.rs similarity index 100% rename from utils/codegen/docker/rgen/src/common/mod.rs rename to utils/codegen/codegen-rust/rgen/src/common/mod.rs diff --git a/utils/codegen/docker/rgen/src/conversion/bin.rs b/utils/codegen/codegen-rust/rgen/src/conversion/bin.rs similarity index 100% rename from utils/codegen/docker/rgen/src/conversion/bin.rs rename to utils/codegen/codegen-rust/rgen/src/conversion/bin.rs diff --git a/utils/codegen/docker/rgen/src/conversion/builder.rs b/utils/codegen/codegen-rust/rgen/src/conversion/builder.rs similarity index 100% rename from utils/codegen/docker/rgen/src/conversion/builder.rs rename to utils/codegen/codegen-rust/rgen/src/conversion/builder.rs diff --git a/utils/codegen/docker/rgen/src/conversion/mod.rs b/utils/codegen/codegen-rust/rgen/src/conversion/mod.rs similarity index 100% rename from utils/codegen/docker/rgen/src/conversion/mod.rs rename to utils/codegen/codegen-rust/rgen/src/conversion/mod.rs diff --git a/utils/codegen/docker/rgen/src/conversion/template.rs b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs similarity index 100% rename from utils/codegen/docker/rgen/src/conversion/template.rs rename to utils/codegen/codegen-rust/rgen/src/conversion/template.rs diff --git a/utils/codegen/docker/rgen/src/conversion/utils.rs b/utils/codegen/codegen-rust/rgen/src/conversion/utils.rs similarity index 100% rename from utils/codegen/docker/rgen/src/conversion/utils.rs rename to utils/codegen/codegen-rust/rgen/src/conversion/utils.rs diff --git a/utils/codegen/docker/rgen/src/lib.rs b/utils/codegen/codegen-rust/rgen/src/lib.rs similarity index 100% rename from utils/codegen/docker/rgen/src/lib.rs rename to utils/codegen/codegen-rust/rgen/src/lib.rs diff --git a/utils/codegen/docker/rgen/src/msgs/bin.rs b/utils/codegen/codegen-rust/rgen/src/msgs/bin.rs similarity index 100% rename from utils/codegen/docker/rgen/src/msgs/bin.rs rename to utils/codegen/codegen-rust/rgen/src/msgs/bin.rs diff --git a/utils/codegen/docker/rgen/src/msgs/builder.rs b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs similarity index 100% rename from utils/codegen/docker/rgen/src/msgs/builder.rs rename to utils/codegen/codegen-rust/rgen/src/msgs/builder.rs diff --git a/utils/codegen/docker/rgen/src/msgs/mod.rs b/utils/codegen/codegen-rust/rgen/src/msgs/mod.rs similarity index 100% rename from utils/codegen/docker/rgen/src/msgs/mod.rs rename to utils/codegen/codegen-rust/rgen/src/msgs/mod.rs diff --git a/utils/codegen/docker/rgen/src/msgs/template.rs b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs similarity index 100% rename from utils/codegen/docker/rgen/src/msgs/template.rs rename to utils/codegen/codegen-rust/rgen/src/msgs/template.rs diff --git a/utils/codegen/docker/rgen/src/msgs/utils.rs b/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs similarity index 100% rename from utils/codegen/docker/rgen/src/msgs/utils.rs rename to utils/codegen/codegen-rust/rgen/src/msgs/utils.rs diff --git a/utils/codegen/docker/rgen/tests/conversion.rs b/utils/codegen/codegen-rust/rgen/tests/conversion.rs similarity index 100% rename from utils/codegen/docker/rgen/tests/conversion.rs rename to utils/codegen/codegen-rust/rgen/tests/conversion.rs diff --git a/utils/codegen/docker/rgen/tests/msgs.rs b/utils/codegen/codegen-rust/rgen/tests/msgs.rs similarity index 100% rename from utils/codegen/docker/rgen/tests/msgs.rs rename to utils/codegen/codegen-rust/rgen/tests/msgs.rs diff --git a/utils/codegen/docker/rgen/tests/utils.rs b/utils/codegen/codegen-rust/rgen/tests/utils.rs similarity index 100% rename from utils/codegen/docker/rgen/tests/utils.rs rename to utils/codegen/codegen-rust/rgen/tests/utils.rs From b3fd2183878e013fb02da61b1e43d9dfc9d710ee Mon Sep 17 00:00:00 2001 From: v0-e Date: Tue, 4 Jun 2024 21:54:29 +0100 Subject: [PATCH 12/22] rgen: Fix helper scripts comments --- .vscode/launch.json | 4 ++-- utils/codegen/codegen-rust/asn1ToConversionHeader.py | 10 +++++----- utils/codegen/codegen-rust/asn1ToRosMsg.py | 6 +++--- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/.vscode/launch.json b/.vscode/launch.json index 7def9956e..f01f710be 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -124,7 +124,7 @@ "args": [ "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", - "-t", "cam", + "-m", "cam", "-o", "etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion" ], "console": "integratedTerminal", @@ -139,7 +139,7 @@ "args": [ "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", - "-t", "denm", + "-m", "denm", "-o", "etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion" ], "console": "integratedTerminal", diff --git a/utils/codegen/codegen-rust/asn1ToConversionHeader.py b/utils/codegen/codegen-rust/asn1ToConversionHeader.py index a1ca15d65..dffd2b2e6 100755 --- a/utils/codegen/codegen-rust/asn1ToConversionHeader.py +++ b/utils/codegen/codegen-rust/asn1ToConversionHeader.py @@ -40,13 +40,13 @@ def parseCli(): """ parser = argparse.ArgumentParser( - description="Creates ROS .msg files from ASN1 definitions.", + description="Creates conversion headers from ASN1 definitions.", formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument("files", type=str, nargs="+", help="ASN1 files") parser.add_argument("-o", "--output-dir", type=str, required=True, help="output directory") parser.add_argument("-td", "--temp-dir", type=str, default=None, help="temporary directory for mounting files to container; uses tempfile by default") - parser.add_argument("-t", "--message", type=str, required=True, help="message name") + parser.add_argument("-m", "--message", type=str, required=True, help="message name") parser.add_argument("-di", "--docker-image", type=str, default="ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen", help="rgen Docker image") args = parser.parse_args() @@ -60,7 +60,7 @@ def main(): # create output directory os.makedirs(args.output_dir, exist_ok=True) - # create temporary directories for running asn1c in docker container + # create temporary directories for running rgen in docker container with tempfile.TemporaryDirectory() as temp_input_dir: with tempfile.TemporaryDirectory() as temp_output_dir: @@ -77,10 +77,10 @@ def main(): for f in args.files: shutil.copy(f, container_input_dir) - # run asn1c docker container to generate header and source files + # run rgen docker container to generate conversion headers subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'conversion-headers', args.message], check=True) - # move generated header and source files to output directories + # move generated conversion headers to output directories for f in glob.glob(os.path.join(container_output_dir, "*.h")): shutil.move(f, os.path.join(args.output_dir, os.path.basename(f))) diff --git a/utils/codegen/codegen-rust/asn1ToRosMsg.py b/utils/codegen/codegen-rust/asn1ToRosMsg.py index 102fe44fe..1a2fc6b78 100755 --- a/utils/codegen/codegen-rust/asn1ToRosMsg.py +++ b/utils/codegen/codegen-rust/asn1ToRosMsg.py @@ -59,7 +59,7 @@ def main(): # create output directory os.makedirs(args.output_dir, exist_ok=True) - # create temporary directories for running asn1c in docker container + # create temporary directories for running rgen in docker container with tempfile.TemporaryDirectory() as temp_input_dir: with tempfile.TemporaryDirectory() as temp_output_dir: @@ -76,10 +76,10 @@ def main(): for f in args.files: shutil.copy(f, container_input_dir) - # run asn1c docker container to generate header and source files + # run rgen docker container to generate .msg files subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'msgs', ""], check=True) - # move generated header and source files to output directories + # move generated ROS .msg files to output directories for f in glob.glob(os.path.join(container_output_dir, "*.msg")): shutil.move(f, os.path.join(args.output_dir, os.path.basename(f))) From 79689fd0624d2aa74cb5997ebb39243427ad40b2 Mon Sep 17 00:00:00 2001 From: v0-e Date: Wed, 5 Jun 2024 19:39:09 +0100 Subject: [PATCH 13/22] rgen: Match newlines/variable order with Python gen --- .../msg/AccelerationConfidence.msg | 3 +- .../msg/AccelerationControl.msg | 2 +- .../msg/AccidentSubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/ActionID.msg | 7 -- ...seWeatherConditionAdhesionSubCauseCode.msg | 3 +- ...ionExtremeWeatherConditionSubCauseCode.msg | 3 +- ...therConditionPrecipitationSubCauseCode.msg | 3 +- ...WeatherConditionVisibilitySubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/Altitude.msg | 7 -- .../etsi_its_cam_msgs/msg/AltitudeValue.msg | 3 +- .../etsi_its_cam_msgs/msg/BasicContainer.msg | 7 -- .../BasicVehicleContainerHighFrequency.msg | 35 ++------- .../msg/BasicVehicleContainerLowFrequency.msg | 8 -- etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg | 6 -- .../etsi_its_cam_msgs/msg/CamParameters.msg | 13 +--- .../etsi_its_cam_msgs/msg/CauseCode.msg | 7 -- .../etsi_its_cam_msgs/msg/CauseCodeType.msg | 3 +- .../msg/CenDsrcTollingZone.msg | 10 +-- .../etsi_its_cam_msgs/msg/ClosedLanes.msg | 14 +--- .../msg/CollisionRiskSubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/CoopAwareness.msg | 7 -- .../etsi_its_cam_msgs/msg/Curvature.msg | 7 -- .../etsi_its_cam_msgs/msg/CurvatureValue.msg | 3 +- .../msg/DangerousEndOfQueueSubCauseCode.msg | 3 +- .../msg/DangerousGoodsBasic.msg | 12 +-- .../msg/DangerousGoodsContainer.msg | 6 -- .../msg/DangerousGoodsExtended.msg | 16 +--- .../msg/DangerousSituationSubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/DeltaAltitude.msg | 3 +- .../etsi_its_cam_msgs/msg/DeltaLatitude.msg | 3 +- .../etsi_its_cam_msgs/msg/DeltaLongitude.msg | 3 +- .../msg/DeltaReferencePosition.msg | 8 -- .../msg/EmergencyContainer.msg | 12 +-- .../msg/EmergencyPriority.msg | 2 +- ...mergencyVehicleApproachingSubCauseCode.msg | 3 +- .../msg/EnergyStorageType.msg | 2 +- .../etsi_its_cam_msgs/msg/EventPoint.msg | 10 +-- .../etsi_its_cam_msgs/msg/ExteriorLights.msg | 2 +- .../msg/GenerationDeltaTime.msg | 3 +- ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 3 +- ...dousLocationDangerousCurveSubCauseCode.msg | 3 +- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 3 +- ...usLocationSurfaceConditionSubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/Heading.msg | 7 -- .../msg/HeadingConfidence.msg | 3 +- .../etsi_its_cam_msgs/msg/HeadingValue.msg | 11 ++- .../etsi_its_cam_msgs/msg/HeightLonCarr.msg | 3 +- .../msg/HighFrequencyContainer.msg | 6 +- .../HumanPresenceOnTheRoadSubCauseCode.msg | 3 +- .../msg/HumanProblemSubCauseCode.msg | 3 +- .../msg/InformationQuality.msg | 3 +- .../etsi_its_cam_msgs/msg/ItsPduHeader.msg | 7 +- .../etsi_its_cam_msgs/msg/LanePosition.msg | 3 +- .../msg/LateralAcceleration.msg | 7 -- .../msg/LateralAccelerationValue.msg | 3 +- .../etsi_its_cam_msgs/msg/Latitude.msg | 3 +- .../msg/LightBarSirenInUse.msg | 2 +- .../etsi_its_cam_msgs/msg/Longitude.msg | 3 +- .../msg/LongitudinalAcceleration.msg | 7 -- .../msg/LongitudinalAccelerationValue.msg | 3 +- .../msg/LowFrequencyContainer.msg | 3 - .../msg/NumberOfOccupants.msg | 3 +- .../etsi_its_cam_msgs/msg/PathDeltaTime.msg | 3 +- .../etsi_its_cam_msgs/msg/PathPoint.msg | 9 +-- .../msg/PerformanceClass.msg | 3 +- .../etsi_its_cam_msgs/msg/PosCentMass.msg | 3 +- .../msg/PosConfidenceEllipse.msg | 8 -- .../etsi_its_cam_msgs/msg/PosFrontAx.msg | 3 +- .../etsi_its_cam_msgs/msg/PosLonCarr.msg | 3 +- .../etsi_its_cam_msgs/msg/PosPillar.msg | 3 +- .../msg/PositionOfOccupants.msg | 40 +++++----- .../msg/PostCrashSubCauseCode.msg | 3 +- .../msg/ProtectedCommunicationZone.msg | 17 +---- .../etsi_its_cam_msgs/msg/ProtectedZoneID.msg | 1 - .../msg/ProtectedZoneRadius.msg | 3 +- .../etsi_its_cam_msgs/msg/PtActivation.msg | 7 -- .../msg/PtActivationType.msg | 5 +- .../msg/PublicTransportContainer.msg | 9 +-- .../msg/RSUContainerHighFrequency.msg | 8 +- .../msg/ReferencePosition.msg | 9 --- .../msg/RelevanceDistance.msg | 16 ++-- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/RescueContainer.msg | 6 -- .../msg/RoadWorksContainerBasic.msg | 12 +-- .../msg/RoadworksSubCauseCode.msg | 3 +- .../msg/SafetyCarContainer.msg | 15 +--- .../etsi_its_cam_msgs/msg/SemiAxisLength.msg | 3 +- .../etsi_its_cam_msgs/msg/SequenceNumber.msg | 1 - .../msg/SignalViolationSubCauseCode.msg | 3 +- .../msg/SlowVehicleSubCauseCode.msg | 3 +- .../msg/SpecialTransportContainer.msg | 7 -- .../msg/SpecialTransportType.msg | 2 +- .../msg/SpecialVehicleContainer.msg | 21 +++--- etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg | 7 -- .../etsi_its_cam_msgs/msg/SpeedConfidence.msg | 3 +- .../etsi_its_cam_msgs/msg/SpeedLimit.msg | 3 +- .../etsi_its_cam_msgs/msg/SpeedValue.msg | 3 +- .../etsi_its_cam_msgs/msg/StationID.msg | 1 - .../etsi_its_cam_msgs/msg/StationType.msg | 3 +- .../etsi_its_cam_msgs/msg/StationarySince.msg | 8 +- .../msg/StationaryVehicleSubCauseCode.msg | 3 +- .../msg/SteeringWheelAngle.msg | 7 -- .../msg/SteeringWheelAngleConfidence.msg | 3 +- .../msg/SteeringWheelAngleValue.msg | 3 +- .../msg/SubCauseCodeType.msg | 1 - .../etsi_its_cam_msgs/msg/Temperature.msg | 7 +- .../etsi_its_cam_msgs/msg/TimestampIts.msg | 5 +- .../msg/TrafficConditionSubCauseCode.msg | 3 +- .../msg/TransmissionInterval.msg | 3 +- .../etsi_its_cam_msgs/msg/TurningRadius.msg | 5 +- .../msg/ValidityDuration.msg | 3 +- .../msg/VehicleBreakdownSubCauseCode.msg | 3 +- .../msg/VehicleIdentification.msg | 11 +-- .../etsi_its_cam_msgs/msg/VehicleLength.msg | 7 -- .../msg/VehicleLengthValue.msg | 3 +- .../etsi_its_cam_msgs/msg/VehicleMass.msg | 3 +- .../etsi_its_cam_msgs/msg/VehicleRole.msg | 6 +- .../etsi_its_cam_msgs/msg/VehicleWidth.msg | 3 +- .../msg/VerticalAcceleration.msg | 7 -- .../msg/VerticalAccelerationValue.msg | 3 +- .../msg/WheelBaseVehicle.msg | 3 +- .../msg/WrongWayDrivingSubCauseCode.msg | 3 +- .../etsi_its_cam_msgs/msg/YawRate.msg | 7 -- .../etsi_its_cam_msgs/msg/YawRateValue.msg | 3 +- .../msg/AccelerationConfidence.msg | 3 +- .../msg/AccelerationControl.msg | 2 +- .../msg/AccidentSubCauseCode.msg | 3 +- .../etsi_its_denm_msgs/msg/ActionID.msg | 7 -- ...seWeatherConditionAdhesionSubCauseCode.msg | 3 +- ...ionExtremeWeatherConditionSubCauseCode.msg | 3 +- ...therConditionPrecipitationSubCauseCode.msg | 3 +- ...WeatherConditionVisibilitySubCauseCode.msg | 3 +- .../msg/AlacarteContainer.msg | 23 ++---- .../etsi_its_denm_msgs/msg/Altitude.msg | 7 -- .../etsi_its_denm_msgs/msg/AltitudeValue.msg | 3 +- .../etsi_its_denm_msgs/msg/CauseCode.msg | 7 -- .../etsi_its_denm_msgs/msg/CauseCodeType.msg | 3 +- .../msg/CenDsrcTollingZone.msg | 10 +-- .../etsi_its_denm_msgs/msg/ClosedLanes.msg | 14 +--- .../msg/CollisionRiskSubCauseCode.msg | 3 +- .../etsi_its_denm_msgs/msg/Curvature.msg | 7 -- .../etsi_its_denm_msgs/msg/CurvatureValue.msg | 3 +- etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg | 7 -- .../msg/DangerousEndOfQueueSubCauseCode.msg | 3 +- .../msg/DangerousGoodsBasic.msg | 12 +-- .../msg/DangerousGoodsExtended.msg | 16 +--- .../msg/DangerousSituationSubCauseCode.msg | 3 +- ...alizedEnvironmentalNotificationMessage.msg | 15 +--- .../etsi_its_denm_msgs/msg/DeltaAltitude.msg | 3 +- .../etsi_its_denm_msgs/msg/DeltaLatitude.msg | 3 +- .../etsi_its_denm_msgs/msg/DeltaLongitude.msg | 3 +- .../msg/DeltaReferencePosition.msg | 8 -- .../msg/EmergencyPriority.msg | 2 +- ...mergencyVehicleApproachingSubCauseCode.msg | 3 +- .../msg/EnergyStorageType.msg | 2 +- .../etsi_its_denm_msgs/msg/EventPoint.msg | 10 +-- .../etsi_its_denm_msgs/msg/ExteriorLights.msg | 2 +- ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 3 +- ...dousLocationDangerousCurveSubCauseCode.msg | 3 +- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 3 +- ...usLocationSurfaceConditionSubCauseCode.msg | 3 +- .../etsi_its_denm_msgs/msg/Heading.msg | 7 -- .../msg/HeadingConfidence.msg | 3 +- .../etsi_its_denm_msgs/msg/HeadingValue.msg | 11 ++- .../etsi_its_denm_msgs/msg/HeightLonCarr.msg | 3 +- .../HumanPresenceOnTheRoadSubCauseCode.msg | 3 +- .../msg/HumanProblemSubCauseCode.msg | 3 +- .../msg/ImpactReductionContainer.msg | 17 ----- .../msg/InformationQuality.msg | 3 +- .../etsi_its_denm_msgs/msg/ItsPduHeader.msg | 7 +- .../etsi_its_denm_msgs/msg/LanePosition.msg | 3 +- .../msg/LateralAcceleration.msg | 7 -- .../msg/LateralAccelerationValue.msg | 3 +- .../etsi_its_denm_msgs/msg/Latitude.msg | 3 +- .../msg/LightBarSirenInUse.msg | 2 +- .../msg/LocationContainer.msg | 15 +--- .../etsi_its_denm_msgs/msg/Longitude.msg | 3 +- .../msg/LongitudinalAcceleration.msg | 7 -- .../msg/LongitudinalAccelerationValue.msg | 3 +- .../msg/ManagementContainer.msg | 22 +----- .../msg/NumberOfOccupants.msg | 3 +- .../etsi_its_denm_msgs/msg/PathDeltaTime.msg | 3 +- .../etsi_its_denm_msgs/msg/PathPoint.msg | 9 +-- .../msg/PerformanceClass.msg | 3 +- .../etsi_its_denm_msgs/msg/PosCentMass.msg | 3 +- .../msg/PosConfidenceEllipse.msg | 8 -- .../etsi_its_denm_msgs/msg/PosFrontAx.msg | 3 +- .../etsi_its_denm_msgs/msg/PosLonCarr.msg | 3 +- .../etsi_its_denm_msgs/msg/PosPillar.msg | 3 +- .../msg/PositionOfOccupants.msg | 40 +++++----- .../msg/PostCrashSubCauseCode.msg | 3 +- .../msg/ProtectedCommunicationZone.msg | 17 +---- .../msg/ProtectedZoneID.msg | 1 - .../msg/ProtectedZoneRadius.msg | 3 +- .../etsi_its_denm_msgs/msg/PtActivation.msg | 7 -- .../msg/PtActivationType.msg | 5 +- .../msg/ReferencePosition.msg | 9 --- .../msg/RelevanceDistance.msg | 16 ++-- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 3 +- .../msg/RoadWorksContainerExtended.msg | 32 +++----- .../msg/RoadworksSubCauseCode.msg | 3 +- .../etsi_its_denm_msgs/msg/SemiAxisLength.msg | 3 +- .../etsi_its_denm_msgs/msg/SequenceNumber.msg | 1 - .../msg/SignalViolationSubCauseCode.msg | 3 +- .../msg/SituationContainer.msg | 13 +--- .../msg/SlowVehicleSubCauseCode.msg | 3 +- .../msg/SpecialTransportType.msg | 2 +- .../etsi_its_denm_msgs/msg/Speed.msg | 7 -- .../msg/SpeedConfidence.msg | 3 +- .../etsi_its_denm_msgs/msg/SpeedLimit.msg | 3 +- .../etsi_its_denm_msgs/msg/SpeedValue.msg | 3 +- .../etsi_its_denm_msgs/msg/StationID.msg | 1 - .../etsi_its_denm_msgs/msg/StationType.msg | 3 +- .../msg/StationarySince.msg | 8 +- .../msg/StationaryVehicleContainer.msg | 23 ++---- .../msg/StationaryVehicleSubCauseCode.msg | 3 +- .../msg/SteeringWheelAngle.msg | 7 -- .../msg/SteeringWheelAngleConfidence.msg | 3 +- .../msg/SteeringWheelAngleValue.msg | 3 +- .../msg/SubCauseCodeType.msg | 1 - .../etsi_its_denm_msgs/msg/Temperature.msg | 7 +- .../etsi_its_denm_msgs/msg/TimestampIts.msg | 5 +- .../msg/TrafficConditionSubCauseCode.msg | 3 +- .../msg/TransmissionInterval.msg | 3 +- .../etsi_its_denm_msgs/msg/TurningRadius.msg | 5 +- .../msg/ValidityDuration.msg | 3 +- .../msg/VehicleBreakdownSubCauseCode.msg | 3 +- .../msg/VehicleIdentification.msg | 11 +-- .../etsi_its_denm_msgs/msg/VehicleLength.msg | 7 -- .../msg/VehicleLengthValue.msg | 3 +- .../etsi_its_denm_msgs/msg/VehicleMass.msg | 3 +- .../etsi_its_denm_msgs/msg/VehicleRole.msg | 6 +- .../etsi_its_denm_msgs/msg/VehicleWidth.msg | 3 +- .../msg/VerticalAcceleration.msg | 7 -- .../msg/VerticalAccelerationValue.msg | 3 +- .../msg/WheelBaseVehicle.msg | 3 +- .../msg/WrongWayDrivingSubCauseCode.msg | 3 +- .../etsi_its_denm_msgs/msg/YawRate.msg | 7 -- .../etsi_its_denm_msgs/msg/YawRateValue.msg | 3 +- .../codegen-rust/rgen/src/common/mod.rs | 5 +- .../codegen-rust/rgen/src/msgs/template.rs | 58 +++++++++------ .../codegen-rust/rgen/src/msgs/utils.rs | 74 ++++++++----------- 242 files changed, 410 insertions(+), 1132 deletions(-) diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg index 39c273bbd..f01b8f344 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg @@ -28,10 +28,9 @@ ## INTEGER AccelerationConfidence uint8 value - uint8 MIN = 0 uint8 MAX = 102 - uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg index 2c4c19149..8a147710d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg @@ -30,7 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 - uint8 BIT_INDEX_BRAKE_PEDAL_ENGAGED = 0 uint8 BIT_INDEX_GAS_PEDAL_ENGAGED = 1 uint8 BIT_INDEX_EMERGENCY_BRAKE_ENGAGED = 2 @@ -38,3 +37,4 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg index 24d083f87..17db3e428 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AccidentSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 MULTI_VEHICLE_ACCIDENT = 1 uint8 HEAVY_ACCIDENT = 2 @@ -41,3 +39,4 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg index eb29a0f07..14f623b35 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ActionID - StationID originating_station_id - SequenceNumber sequence_number - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 662392eec..08ca22f25 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AdverseWeatherConditionAdhesionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 HEAVY_FROST_ON_ROAD = 1 uint8 FUEL_ON_ROAD = 2 @@ -43,3 +41,4 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 15cbe797a..bd619386f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 STRONG_WINDS = 1 uint8 DAMAGING_HAIL = 2 @@ -39,3 +37,4 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index e1aa73660..ec4889e8f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -28,11 +28,10 @@ ## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 102915f9b..512dbd14a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AdverseWeatherConditionVisibilitySubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 FOG = 1 uint8 SMOKE = 2 @@ -41,3 +39,4 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg index 594d9d37c..18a7e620d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Altitude - AltitudeValue altitude_value - AltitudeConfidence altitude_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg index 5fb1d7c33..c804dadb1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg @@ -28,10 +28,9 @@ ## INTEGER AltitudeValue int32 value - int32 MIN = -100000 int32 MAX = 800001 - int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg index b324717c8..77e4ac3ea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE BasicContainer .extensible - StationType station_type - ReferencePosition reference_position - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg index 013210e53..56da03917 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg @@ -26,63 +26,42 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE BasicVehicleContainerHighFrequency - Heading heading - Speed speed - DriveDirection drive_direction - VehicleLength vehicle_length - VehicleWidth vehicle_width - LongitudinalAcceleration longitudinal_acceleration - Curvature curvature - CurvatureCalculationMode curvature_calculation_mode - YawRate yaw_rate - -bool acceleration_control_is_present AccelerationControl acceleration_control +bool acceleration_control_is_present - -bool lane_position_is_present LanePosition lane_position +bool lane_position_is_present - -bool steering_wheel_angle_is_present SteeringWheelAngle steering_wheel_angle +bool steering_wheel_angle_is_present - -bool lateral_acceleration_is_present LateralAcceleration lateral_acceleration +bool lateral_acceleration_is_present - -bool vertical_acceleration_is_present VerticalAcceleration vertical_acceleration +bool vertical_acceleration_is_present - -bool performance_class_is_present PerformanceClass performance_class +bool performance_class_is_present - -bool cen_dsrc_tolling_zone_is_present CenDsrcTollingZone cen_dsrc_tolling_zone - - - - - +bool cen_dsrc_tolling_zone_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg index 426397172..8f964674b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg @@ -26,17 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE BasicVehicleContainerLowFrequency - VehicleRole vehicle_role - ExteriorLights exterior_lights - PathHistory path_history - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg index f5230f84c..d83efd37f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg @@ -30,11 +30,5 @@ ItsPduHeader header - CoopAwareness cam - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg index b6b4461ae..124001ca4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg @@ -26,22 +26,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE CamParameters .extensible - BasicContainer basic_container - HighFrequencyContainer high_frequency_container - -bool low_frequency_container_is_present LowFrequencyContainer low_frequency_container +bool low_frequency_container_is_present - -bool special_vehicle_container_is_present SpecialVehicleContainer special_vehicle_container - - - - - +bool special_vehicle_container_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg index 973c89781..46fa8aed4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE CauseCode .extensible - CauseCodeType cause_code - SubCauseCodeType sub_cause_code - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg index f873754cc..0db806cca 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg @@ -28,10 +28,8 @@ ## INTEGER CauseCodeType uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 RESERVED = 0 uint8 TRAFFIC_CONDITION = 1 uint8 ACCIDENT = 2 @@ -59,3 +57,4 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg index a05df3837..96a17295f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg @@ -26,18 +26,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE CenDsrcTollingZone .extensible - Latitude protected_zone_latitude - Longitude protected_zone_longitude - -bool cen_dsrc_tolling_zone_id_is_present CenDsrcTollingZoneID cen_dsrc_tolling_zone_id - - - - - +bool cen_dsrc_tolling_zone_id_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg index 77134bbcd..55b9c5f22 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg @@ -26,20 +26,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ClosedLanes .extensible - -bool innerhard_shoulder_status_is_present HardShoulderStatus innerhard_shoulder_status +bool innerhard_shoulder_status_is_present - -bool outerhard_shoulder_status_is_present HardShoulderStatus outerhard_shoulder_status +bool outerhard_shoulder_status_is_present - -bool driving_lane_status_is_present DrivingLaneStatus driving_lane_status - - - - - +bool driving_lane_status_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg index df3412e0c..9181725da 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER CollisionRiskSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg index 4b7c2596d..518be360d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE CoopAwareness - GenerationDeltaTime generation_delta_time - CamParameters cam_parameters - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg index 1786b4977..6aead5fdf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Curvature - CurvatureValue curvature_value - CurvatureConfidence curvature_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg index 9d1974f26..3b87030fe 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg @@ -28,9 +28,8 @@ ## INTEGER CurvatureValue int16 value - int16 MIN = -1023 int16 MAX = 1023 - int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index beea5c8a1..d32f91b10 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER DangerousEndOfQueueSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg index 8a9140b26..9213942db 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg @@ -28,12 +28,12 @@ ## ENUMERATED DangerousGoodsBasic uint8 value -uint8 EXPLOSIVES1 = 0 -uint8 EXPLOSIVES2 = 1 -uint8 EXPLOSIVES3 = 2 -uint8 EXPLOSIVES4 = 3 -uint8 EXPLOSIVES5 = 4 -uint8 EXPLOSIVES6 = 5 +uint8 EXPLOSIVES_1 = 0 +uint8 EXPLOSIVES_2 = 1 +uint8 EXPLOSIVES_3 = 2 +uint8 EXPLOSIVES_4 = 3 +uint8 EXPLOSIVES_5 = 4 +uint8 EXPLOSIVES_6 = 5 uint8 FLAMMABLE_GASES = 6 uint8 NON_FLAMMABLE_GASES = 7 uint8 TOXIC_GASES = 8 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg index 0f5c1e091..6ac877f17 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg @@ -26,11 +26,5 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DangerousGoodsContainer - DangerousGoodsBasic dangerous_goods_basic - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg index 4a38b0f84..cd1bbd0d9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg @@ -26,38 +26,28 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DangerousGoodsExtended .extensible - DangerousGoodsBasic dangerous_goods_type - uint16 un_number uint16 UN_NUMBER_MIN = 0 uint16 UN_NUMBER_MAX = 9999 bool elevated_temperature - bool tunnels_restricted - bool limited_quantity - -bool emergency_action_code_is_present string emergency_action_code +bool emergency_action_code_is_present uint8 EMERGENCY_ACTION_CODE_LENGTH_MIN = 1 uint8 EMERGENCY_ACTION_CODE_LENGTH_MAX = 24 -bool phone_number_is_present PhoneNumber phone_number +bool phone_number_is_present - -bool company_name_is_present string company_name +bool company_name_is_present uint8 COMPANY_NAME_LENGTH_MIN = 1 uint8 COMPANY_NAME_LENGTH_MAX = 24 - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg index ef126f527..fc81522ad 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER DangerousSituationSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 EMERGENCY_ELECTRONIC_BRAKE_ENGAGED = 1 uint8 PRE_CRASH_SYSTEM_ENGAGED = 2 @@ -40,3 +38,4 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg index 5ee397cad..9e3df25b6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg @@ -28,10 +28,9 @@ ## INTEGER DeltaAltitude int16 value - int16 MIN = -12700 int16 MAX = 12800 - int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg index 561ca3b33..8a72373f9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg @@ -28,10 +28,9 @@ ## INTEGER DeltaLatitude int32 value - int32 MIN = -131071 int32 MAX = 131072 - int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg index 0b4a95b64..d32f293d9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg @@ -28,10 +28,9 @@ ## INTEGER DeltaLongitude int32 value - int32 MIN = -131071 int32 MAX = 131072 - int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg index 31a9f06dc..7ae8cd306 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg @@ -26,17 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DeltaReferencePosition - DeltaLatitude delta_latitude - DeltaLongitude delta_longitude - DeltaAltitude delta_altitude - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg index 4e140cbe1..3be9e58ee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg @@ -26,19 +26,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE EmergencyContainer - LightBarSirenInUse light_bar_siren_in_use - -bool incident_indication_is_present CauseCode incident_indication +bool incident_indication_is_present - -bool emergency_priority_is_present EmergencyPriority emergency_priority - - - - - +bool emergency_priority_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg index c81f118e7..d521c7c58 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg @@ -30,6 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 - uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 88df9871d..5f1439a2d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -28,10 +28,9 @@ ## INTEGER EmergencyVehicleApproachingSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg index 591c76718..cd3856bf9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg @@ -30,7 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 - uint8 BIT_INDEX_HYDROGEN_STORAGE = 0 uint8 BIT_INDEX_ELECTRIC_ENERGY_STORAGE = 1 uint8 BIT_INDEX_LIQUID_PROPANE_GAS = 2 @@ -38,3 +37,4 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg index 1643fe007..c0fcc5bae 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg @@ -26,18 +26,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE EventPoint - DeltaReferencePosition event_position - -bool event_delta_time_is_present PathDeltaTime event_delta_time - +bool event_delta_time_is_present InformationQuality information_quality - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg index e865cb77d..d191062ca 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg @@ -30,7 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 8 - uint8 BIT_INDEX_LOW_BEAM_HEADLIGHTS_ON = 0 uint8 BIT_INDEX_HIGH_BEAM_HEADLIGHTS_ON = 1 uint8 BIT_INDEX_LEFT_TURN_SIGNAL_ON = 2 @@ -39,3 +38,4 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg index 06ef6b756..3fd33045a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg @@ -28,8 +28,7 @@ ## INTEGER GenerationDeltaTime uint16 value - uint16 MIN = 0 uint16 MAX = 65535 - uint16 ONE_MILLI_SEC = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index ddbc580f8..c7b360731 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index 4d6e18d8c..63495337b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -28,13 +28,12 @@ ## INTEGER HazardousLocationDangerousCurveSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 DANGEROUS_LEFT_TURN_CURVE = 1 uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index 7b7221621..961c2dabb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 SHED_LOAD = 1 uint8 PARTS_OF_VEHICLES = 2 @@ -40,3 +38,4 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index e29146cd5..7aea67d58 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER HazardousLocationSurfaceConditionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 ROCKFALLS = 1 uint8 EARTHQUAKE_DAMAGE = 2 @@ -42,3 +40,4 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg index 95c48bc5f..961b9a6c6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Heading - HeadingValue heading_value - HeadingConfidence heading_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg index c8e97c562..378afb7c0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg @@ -28,11 +28,10 @@ ## INTEGER HeadingConfidence uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg index 4ead96652..22c0493e4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg @@ -28,12 +28,11 @@ ## INTEGER HeadingValue uint16 value - uint16 MIN = 0 uint16 MAX = 3601 - -uint16 WGS84_NORTH = 0 -uint16 WGS84_EAST = 900 -uint16 WGS84_SOUTH = 1800 -uint16 WGS84_WEST = 2700 +uint16 WGS_84_NORTH = 0 +uint16 WGS_84_EAST = 900 +uint16 WGS_84_SOUTH = 1800 +uint16 WGS_84_WEST = 2700 uint16 UNAVAILABLE = 3601 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg index 4041aa8cd..d5cfb65c4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg @@ -28,9 +28,8 @@ ## INTEGER HeightLonCarr uint8 value - uint8 MIN = 1 uint8 MAX = 100 - uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg index 69473ba68..d278ab9b1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg @@ -26,13 +26,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## CHOICE HighFrequencyContainer .extensible - uint8 choice BasicVehicleContainerHighFrequency basic_vehicle_container_high_frequency -RSUContainerHighFrequency rsu_container_high_frequency - uint8 CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY = 0 -uint8 CHOICE_RSU_CONTAINER_HIGH_FREQUENCY = 1 +RSUContainerHighFrequency rsu_container_high_frequency +uint8 CHOICE_RSU_CONTAINER_HIGH_FREQUENCY = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 317a4b8e0..6b69511e2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -28,11 +28,10 @@ ## INTEGER HumanPresenceOnTheRoadSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg index e5866377f..35e538c4b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg @@ -28,10 +28,9 @@ ## INTEGER HumanProblemSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg index 7ac459b0f..43e2a2799 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg @@ -28,10 +28,9 @@ ## INTEGER InformationQuality uint8 value - uint8 MIN = 0 uint8 MAX = 7 - uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg index e0e95b0c5..b5c4b5740 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg @@ -26,7 +26,6 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ItsPduHeader - uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 uint8 PROTOCOL_VERSION_MAX = 255 @@ -48,10 +47,6 @@ uint8 MESSAGE_ID_EVCSN = 11 uint8 MESSAGE_ID_SAEM = 12 uint8 MESSAGE_ID_RTCMEM = 13 -StationID station_id - - - - +StationID station_id diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg index 2729a0deb..655869fa9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg @@ -28,11 +28,10 @@ ## INTEGER LanePosition int8 value - int8 MIN = -1 int8 MAX = 14 - int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg index a8afa582f..8a7b7678d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE LateralAcceleration - LateralAccelerationValue lateral_acceleration_value - AccelerationConfidence lateral_acceleration_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg index db9cf92b6..329b4a154 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg @@ -28,10 +28,9 @@ ## INTEGER LateralAccelerationValue int16 value - int16 MIN = -160 int16 MAX = 161 - int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg index 0b95abe96..918857d42 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg @@ -28,10 +28,9 @@ ## INTEGER Latitude int32 value - int32 MIN = -900000000 int32 MAX = 900000001 - int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg index 464b1bb86..d86ad6e16 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg @@ -30,6 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 - uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg index 9f0bbac8b..21539c674 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg @@ -28,10 +28,9 @@ ## INTEGER Longitude int32 value - int32 MIN = -1800000000 int32 MAX = 1800000001 - int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg index 501b57fba..4880b8e99 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE LongitudinalAcceleration - LongitudinalAccelerationValue longitudinal_acceleration_value - AccelerationConfidence longitudinal_acceleration_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg index 90a6d1c80..30653502d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg @@ -28,10 +28,9 @@ ## INTEGER LongitudinalAccelerationValue int16 value - int16 MIN = -160 int16 MAX = 161 - int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg index 549b35262..973ebcabc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg @@ -26,11 +26,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## CHOICE LowFrequencyContainer .extensible - uint8 choice BasicVehicleContainerLowFrequency basic_vehicle_container_low_frequency - uint8 CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY = 0 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg index cba00ac08..7b2e01aa6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg @@ -28,9 +28,8 @@ ## INTEGER NumberOfOccupants uint8 value - uint8 MIN = 0 uint8 MAX = 127 - uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg index e07b00515..b5e9697e9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg @@ -28,8 +28,7 @@ ## INTEGER PathDeltaTime int64 value - int64 MIN = 1 int64 MAX = 65535 - int64 TEN_MILLI_SECONDS_IN_PAST = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg index 3a66f5c33..87ce1b575 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg @@ -26,15 +26,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PathPoint - DeltaReferencePosition path_position - -bool path_delta_time_is_present PathDeltaTime path_delta_time - - - - - +bool path_delta_time_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg index 84e9690d6..8cf5eeec5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg @@ -28,10 +28,9 @@ ## INTEGER PerformanceClass uint8 value - uint8 MIN = 0 uint8 MAX = 7 - uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg index a4e5238ff..1e9128d00 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg @@ -28,9 +28,8 @@ ## INTEGER PosCentMass uint8 value - uint8 MIN = 1 uint8 MAX = 63 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg index ebf822654..aeb665ecc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg @@ -26,17 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PosConfidenceEllipse - SemiAxisLength semi_major_confidence - SemiAxisLength semi_minor_confidence - HeadingValue semi_major_orientation - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg index bf9032811..606b67039 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg @@ -28,9 +28,8 @@ ## INTEGER PosFrontAx uint8 value - uint8 MIN = 1 uint8 MAX = 20 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg index 9b6643818..b01c3342b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg @@ -28,9 +28,8 @@ ## INTEGER PosLonCarr uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg index dea1c83a8..3f3cc73e9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg @@ -28,9 +28,8 @@ ## INTEGER PosPillar uint8 value - uint8 MIN = 1 uint8 MAX = 30 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg index 5320b5167..5837d8005 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg @@ -30,24 +30,24 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 20 +uint8 BIT_INDEX_ROW_1_LEFT_OCCUPIED = 0 +uint8 BIT_INDEX_ROW_1_RIGHT_OCCUPIED = 1 +uint8 BIT_INDEX_ROW_1_MID_OCCUPIED = 2 +uint8 BIT_INDEX_ROW_1_NOT_DETECTABLE = 3 +uint8 BIT_INDEX_ROW_1_NOT_PRESENT = 4 +uint8 BIT_INDEX_ROW_2_LEFT_OCCUPIED = 5 +uint8 BIT_INDEX_ROW_2_RIGHT_OCCUPIED = 6 +uint8 BIT_INDEX_ROW_2_MID_OCCUPIED = 7 +uint8 BIT_INDEX_ROW_2_NOT_DETECTABLE = 8 +uint8 BIT_INDEX_ROW_2_NOT_PRESENT = 9 +uint8 BIT_INDEX_ROW_3_LEFT_OCCUPIED = 10 +uint8 BIT_INDEX_ROW_3_RIGHT_OCCUPIED = 11 +uint8 BIT_INDEX_ROW_3_MID_OCCUPIED = 12 +uint8 BIT_INDEX_ROW_3_NOT_DETECTABLE = 13 +uint8 BIT_INDEX_ROW_3_NOT_PRESENT = 14 +uint8 BIT_INDEX_ROW_4_LEFT_OCCUPIED = 15 +uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 +uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 +uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 +uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 -uint8 BIT_INDEX_ROW1_LEFT_OCCUPIED = 0 -uint8 BIT_INDEX_ROW1_RIGHT_OCCUPIED = 1 -uint8 BIT_INDEX_ROW1_MID_OCCUPIED = 2 -uint8 BIT_INDEX_ROW1_NOT_DETECTABLE = 3 -uint8 BIT_INDEX_ROW1_NOT_PRESENT = 4 -uint8 BIT_INDEX_ROW2_LEFT_OCCUPIED = 5 -uint8 BIT_INDEX_ROW2_RIGHT_OCCUPIED = 6 -uint8 BIT_INDEX_ROW2_MID_OCCUPIED = 7 -uint8 BIT_INDEX_ROW2_NOT_DETECTABLE = 8 -uint8 BIT_INDEX_ROW2_NOT_PRESENT = 9 -uint8 BIT_INDEX_ROW3_LEFT_OCCUPIED = 10 -uint8 BIT_INDEX_ROW3_RIGHT_OCCUPIED = 11 -uint8 BIT_INDEX_ROW3_MID_OCCUPIED = 12 -uint8 BIT_INDEX_ROW3_NOT_DETECTABLE = 13 -uint8 BIT_INDEX_ROW3_NOT_PRESENT = 14 -uint8 BIT_INDEX_ROW4_LEFT_OCCUPIED = 15 -uint8 BIT_INDEX_ROW4_RIGHT_OCCUPIED = 16 -uint8 BIT_INDEX_ROW4_MID_OCCUPIED = 17 -uint8 BIT_INDEX_ROW4_NOT_DETECTABLE = 18 -uint8 BIT_INDEX_ROW4_NOT_PRESENT = 19 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg index 624da3885..8a1777231 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER PostCrashSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg index 13bdb1cce..d8ac4b043 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg @@ -26,29 +26,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ProtectedCommunicationZone .extensible - ProtectedZoneType protected_zone_type - -bool expiry_time_is_present TimestampIts expiry_time - +bool expiry_time_is_present Latitude protected_zone_latitude - Longitude protected_zone_longitude - -bool protected_zone_radius_is_present ProtectedZoneRadius protected_zone_radius +bool protected_zone_radius_is_present - -bool protected_zone_id_is_present ProtectedZoneID protected_zone_id - - - - - +bool protected_zone_id_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg index 6597bca31..ae4c41709 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg @@ -28,7 +28,6 @@ ## INTEGER ProtectedZoneID uint32 value - uint32 MIN = 0 uint32 MAX = 134217727 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg index 2c685a0a7..e2a5a4e8e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg @@ -28,8 +28,7 @@ ## INTEGER ProtectedZoneRadius int64 value - int64 MIN = 1 int64 MAX = 255 - int64 ONE_METER = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg index ce76306de..f6fdbe3ea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PtActivation - PtActivationType pt_activation_type - PtActivationData pt_activation_data - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg index 889884086..6a7a5bda6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg @@ -28,10 +28,9 @@ ## INTEGER PtActivationType uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNDEFINED_CODING_TYPE = 0 -uint8 R09_16_CODING_TYPE = 1 +uint8 R_09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg index 2b75db37f..99d897d78 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg @@ -26,15 +26,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PublicTransportContainer - EmbarkationStatus embarkation_status - -bool pt_activation_is_present PtActivation pt_activation - - - - - +bool pt_activation_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg index 3d14fdfec..3e64de180 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg @@ -26,12 +26,6 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE RSUContainerHighFrequency .extensible - -bool protected_communication_zones_rsu_is_present ProtectedCommunicationZonesRSU protected_communication_zones_rsu - - - - - +bool protected_communication_zones_rsu_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg index dd647f7d2..07a4e8e6d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg @@ -26,20 +26,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ReferencePosition - Latitude latitude - Longitude longitude - PosConfidenceEllipse position_confidence_ellipse - Altitude altitude - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg index 23fe60283..443ca5e6f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg @@ -28,12 +28,12 @@ ## ENUMERATED RelevanceDistance uint8 value -uint8 LESS_THAN50M = 0 -uint8 LESS_THAN100M = 1 -uint8 LESS_THAN200M = 2 -uint8 LESS_THAN500M = 3 -uint8 LESS_THAN1000M = 4 -uint8 LESS_THAN5KM = 5 -uint8 LESS_THAN10KM = 6 -uint8 OVER10KM = 7 +uint8 LESS_THAN_50M = 0 +uint8 LESS_THAN_100M = 1 +uint8 LESS_THAN_200M = 2 +uint8 LESS_THAN_500M = 3 +uint8 LESS_THAN_1000M = 4 +uint8 LESS_THAN_5KM = 5 +uint8 LESS_THAN_10KM = 6 +uint8 OVER_10KM = 7 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index 360516e4f..bd3a50097 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -28,13 +28,12 @@ ## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLES = 1 uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg index 0801c8305..818dd2f51 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg @@ -26,11 +26,5 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE RescueContainer - LightBarSirenInUse light_bar_siren_in_use - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg index 851fe39e3..d9e2fe03f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg @@ -26,19 +26,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE RoadWorksContainerBasic - -bool roadworks_sub_cause_code_is_present RoadworksSubCauseCode roadworks_sub_cause_code - +bool roadworks_sub_cause_code_is_present LightBarSirenInUse light_bar_siren_in_use - -bool closed_lanes_is_present ClosedLanes closed_lanes - - - - - +bool closed_lanes_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg index 1c70e3429..b6575d73e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER RoadworksSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 MAJOR_ROADWORKS = 1 uint8 ROAD_MARKING_WORK = 2 @@ -39,3 +37,4 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg index 3081c1d65..b419536e9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg @@ -26,23 +26,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE SafetyCarContainer - LightBarSirenInUse light_bar_siren_in_use - -bool incident_indication_is_present CauseCode incident_indication +bool incident_indication_is_present - -bool traffic_rule_is_present TrafficRule traffic_rule +bool traffic_rule_is_present - -bool speed_limit_is_present SpeedLimit speed_limit - - - - - +bool speed_limit_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg index 00570648c..eaa61cf9e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg @@ -28,10 +28,9 @@ ## INTEGER SemiAxisLength uint16 value - uint16 MIN = 0 uint16 MAX = 4095 - uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg index 46de8a045..27a36a32c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg @@ -28,7 +28,6 @@ ## INTEGER SequenceNumber uint16 value - uint16 MIN = 0 uint16 MAX = 65535 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg index 85cd4c570..0887a5941 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg @@ -28,11 +28,10 @@ ## INTEGER SignalViolationSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg index b2851a5dc..192a08311 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER SlowVehicleSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 MAINTENANCE_VEHICLE = 1 uint8 VEHICLES_SLOWING_TO_LOOK_AT_ACCIDENT = 2 @@ -41,3 +39,4 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg index 663ac4291..2b4b21c05 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE SpecialTransportContainer - SpecialTransportType special_transport_type - LightBarSirenInUse light_bar_siren_in_use - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg index 11895303b..743017c33 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg @@ -30,8 +30,8 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 4 - uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg index 4a98f8e8a..c3c2bd971 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg @@ -26,23 +26,26 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## CHOICE SpecialVehicleContainer .extensible - uint8 choice PublicTransportContainer public_transport_container -SpecialTransportContainer special_transport_container -DangerousGoodsContainer dangerous_goods_container -RoadWorksContainerBasic road_works_container_basic -RescueContainer rescue_container -EmergencyContainer emergency_container -SafetyCarContainer safety_car_container - uint8 CHOICE_PUBLIC_TRANSPORT_CONTAINER = 0 + +SpecialTransportContainer special_transport_container uint8 CHOICE_SPECIAL_TRANSPORT_CONTAINER = 1 + +DangerousGoodsContainer dangerous_goods_container uint8 CHOICE_DANGEROUS_GOODS_CONTAINER = 2 + +RoadWorksContainerBasic road_works_container_basic uint8 CHOICE_ROAD_WORKS_CONTAINER_BASIC = 3 + +RescueContainer rescue_container uint8 CHOICE_RESCUE_CONTAINER = 4 + +EmergencyContainer emergency_container uint8 CHOICE_EMERGENCY_CONTAINER = 5 -uint8 CHOICE_SAFETY_CAR_CONTAINER = 6 +SafetyCarContainer safety_car_container +uint8 CHOICE_SAFETY_CAR_CONTAINER = 6 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg index 23aef070f..f603b1dcc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Speed - SpeedValue speed_value - SpeedConfidence speed_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg index 0b8c93e95..04391b581 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg @@ -28,11 +28,10 @@ ## INTEGER SpeedConfidence uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg index e71840559..b54a37c8a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg @@ -28,8 +28,7 @@ ## INTEGER SpeedLimit uint8 value - uint8 MIN = 1 uint8 MAX = 255 - uint8 ONE_KM_PER_HOUR = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg index f61585f55..15c55d7a2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg @@ -28,10 +28,9 @@ ## INTEGER SpeedValue uint16 value - uint16 MIN = 0 uint16 MAX = 16383 - uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg index 8b688adc3..9e5dc24dd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg @@ -28,7 +28,6 @@ ## INTEGER StationID uint32 value - uint32 MIN = 0 uint32 MAX = 4294967295 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg index 5674dcae4..08547aaa6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg @@ -28,10 +28,8 @@ ## INTEGER StationType uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNKNOWN = 0 uint8 PEDESTRIAN = 1 uint8 CYCLIST = 2 @@ -45,3 +43,4 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg index 1e851253c..a35450fd1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg @@ -28,8 +28,8 @@ ## ENUMERATED StationarySince uint8 value -uint8 LESS_THAN1_MINUTE = 0 -uint8 LESS_THAN2_MINUTES = 1 -uint8 LESS_THAN15_MINUTES = 2 -uint8 EQUAL_OR_GREATER15_MINUTES = 3 +uint8 LESS_THAN_1_MINUTE = 0 +uint8 LESS_THAN_2_MINUTES = 1 +uint8 LESS_THAN_15_MINUTES = 2 +uint8 EQUAL_OR_GREATER_15_MINUTES = 3 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg index adf013ce3..3b8bdb501 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -28,13 +28,12 @@ ## INTEGER StationaryVehicleSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 HUMAN_PROBLEM = 1 uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg index 7d033b9dd..b38f81f0d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE SteeringWheelAngle - SteeringWheelAngleValue steering_wheel_angle_value - SteeringWheelAngleConfidence steering_wheel_angle_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg index 836d42c04..c693654a8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg @@ -28,10 +28,9 @@ ## INTEGER SteeringWheelAngleConfidence uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg index afb11301f..2d6e2b766 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg @@ -28,11 +28,10 @@ ## INTEGER SteeringWheelAngleValue int16 value - int16 MIN = -511 int16 MAX = 512 - int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg index 76b818aae..305bb683a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg @@ -28,7 +28,6 @@ ## INTEGER SubCauseCodeType uint8 value - uint8 MIN = 0 uint8 MAX = 255 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg index 2259fe2cf..cc883d230 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg @@ -28,10 +28,9 @@ ## INTEGER Temperature int8 value - int8 MIN = -60 int8 MAX = 67 - -int8 EQUAL_OR_SMALLER_THAN_MINUS60_DEG = -60 +int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 int8 ONE_DEGREE_CELSIUS = 1 -int8 EQUAL_OR_GREATER_THAN67_DEG = 67 +int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg index 6ebee0fb7..d41d01815 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg @@ -28,9 +28,8 @@ ## INTEGER TimestampIts uint64 value - uint64 MIN = 0 uint64 MAX = 4398046511103 +uint64 UTC_START_OF_2004 = 0 +uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 -uint64 UTC_START_OF2004 = 0 -uint64 ONE_MILLISEC_AFTER_UTC_START_OF2004 = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg index 3bf2c7572..310a34eb7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER TrafficConditionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 INCREASED_VOLUME_OF_TRAFFIC = 1 uint8 TRAFFIC_JAM_SLOWLY_INCREASING = 2 @@ -41,3 +39,4 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg index 76153c55f..6b411b09e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg @@ -28,9 +28,8 @@ ## INTEGER TransmissionInterval uint16 value - uint16 MIN = 1 uint16 MAX = 10000 - uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg index 7ca5596d8..50a96cf26 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg @@ -28,9 +28,8 @@ ## INTEGER TurningRadius uint8 value - uint8 MIN = 1 uint8 MAX = 255 - -uint8 POINT4_METERS = 1 +uint8 POINT_4_METERS = 1 uint8 UNAVAILABLE = 255 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg index 806532404..494e18e75 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg @@ -28,9 +28,8 @@ ## INTEGER ValidityDuration uint32 value - uint32 MIN = 0 uint32 MAX = 86400 - uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg index 79ed4c0b0..8ad8d31f5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER VehicleBreakdownSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 LACK_OF_FUEL = 1 uint8 LACK_OF_BATTERY_POWER = 2 @@ -42,3 +40,4 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg index 73c04c673..ce86ece17 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg @@ -26,16 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE VehicleIdentification .extensible - -bool w_m_inumber_is_present WMInumber w_m_inumber +bool w_m_inumber_is_present - -bool v_ds_is_present VDS v_ds - - - - - +bool v_ds_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg index 513a60967..0efac770f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE VehicleLength - VehicleLengthValue vehicle_length_value - VehicleLengthConfidenceIndication vehicle_length_confidence_indication - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg index 7e43bcf2c..c4136bc96 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg @@ -28,10 +28,9 @@ ## INTEGER VehicleLengthValue uint16 value - uint16 MIN = 1 uint16 MAX = 1023 - uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg index c8e936d57..f5895ca82 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg @@ -28,9 +28,8 @@ ## INTEGER VehicleMass uint16 value - uint16 MIN = 1 uint16 MAX = 1024 - uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg index d3a9a2c74..c8aac5c89 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg @@ -41,7 +41,7 @@ uint8 COMMERCIAL = 9 uint8 MILITARY = 10 uint8 ROAD_OPERATOR = 11 uint8 TAXI = 12 -uint8 RESERVED1 = 13 -uint8 RESERVED2 = 14 -uint8 RESERVED3 = 15 +uint8 RESERVED_1 = 13 +uint8 RESERVED_2 = 14 +uint8 RESERVED_3 = 15 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg index 575bb2893..c86ebc997 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg @@ -28,10 +28,9 @@ ## INTEGER VehicleWidth uint8 value - uint8 MIN = 1 uint8 MAX = 62 - uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg index 78515df4c..51e0d5979 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE VerticalAcceleration - VerticalAccelerationValue vertical_acceleration_value - AccelerationConfidence vertical_acceleration_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg index 20e71ad81..692493880 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg @@ -28,10 +28,9 @@ ## INTEGER VerticalAccelerationValue int16 value - int16 MIN = -160 int16 MAX = 161 - int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg index 77d9730b3..e8a16e042 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg @@ -28,9 +28,8 @@ ## INTEGER WheelBaseVehicle uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg index 73b00caaf..df60cdcea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -28,10 +28,9 @@ ## INTEGER WrongWayDrivingSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg index 64e05f9a2..404b07465 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE YawRate - YawRateValue yaw_rate_value - YawRateConfidence yaw_rate_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg index 2a8dbc3e5..86fb2e26b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg @@ -28,11 +28,10 @@ ## INTEGER YawRateValue int16 value - int16 MIN = -32766 int16 MAX = 32767 - int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg index 39c273bbd..f01b8f344 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg @@ -28,10 +28,9 @@ ## INTEGER AccelerationConfidence uint8 value - uint8 MIN = 0 uint8 MAX = 102 - uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg index 2c4c19149..8a147710d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg @@ -30,7 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 - uint8 BIT_INDEX_BRAKE_PEDAL_ENGAGED = 0 uint8 BIT_INDEX_GAS_PEDAL_ENGAGED = 1 uint8 BIT_INDEX_EMERGENCY_BRAKE_ENGAGED = 2 @@ -38,3 +37,4 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg index 24d083f87..17db3e428 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AccidentSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 MULTI_VEHICLE_ACCIDENT = 1 uint8 HEAVY_ACCIDENT = 2 @@ -41,3 +39,4 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg index eb29a0f07..14f623b35 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ActionID - StationID originating_station_id - SequenceNumber sequence_number - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 662392eec..08ca22f25 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AdverseWeatherConditionAdhesionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 HEAVY_FROST_ON_ROAD = 1 uint8 FUEL_ON_ROAD = 2 @@ -43,3 +41,4 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 15cbe797a..bd619386f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 STRONG_WINDS = 1 uint8 DAMAGING_HAIL = 2 @@ -39,3 +37,4 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index e1aa73660..ec4889e8f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -28,11 +28,10 @@ ## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 102915f9b..512dbd14a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER AdverseWeatherConditionVisibilitySubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 FOG = 1 uint8 SMOKE = 2 @@ -41,3 +39,4 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg index 3f09db98f..85bd572f4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg @@ -26,32 +26,21 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE AlacarteContainer .extensible - -bool lane_position_is_present LanePosition lane_position +bool lane_position_is_present - -bool impact_reduction_is_present ImpactReductionContainer impact_reduction +bool impact_reduction_is_present - -bool external_temperature_is_present Temperature external_temperature +bool external_temperature_is_present - -bool road_works_is_present RoadWorksContainerExtended road_works +bool road_works_is_present - -bool positioning_solution_is_present PositioningSolutionType positioning_solution +bool positioning_solution_is_present - -bool stationary_vehicle_is_present StationaryVehicleContainer stationary_vehicle - - - - - +bool stationary_vehicle_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg index 594d9d37c..18a7e620d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Altitude - AltitudeValue altitude_value - AltitudeConfidence altitude_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg index 5fb1d7c33..c804dadb1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg @@ -28,10 +28,9 @@ ## INTEGER AltitudeValue int32 value - int32 MIN = -100000 int32 MAX = 800001 - int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg index 973c89781..46fa8aed4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE CauseCode .extensible - CauseCodeType cause_code - SubCauseCodeType sub_cause_code - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg index f873754cc..0db806cca 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg @@ -28,10 +28,8 @@ ## INTEGER CauseCodeType uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 RESERVED = 0 uint8 TRAFFIC_CONDITION = 1 uint8 ACCIDENT = 2 @@ -59,3 +57,4 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg index a05df3837..96a17295f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg @@ -26,18 +26,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE CenDsrcTollingZone .extensible - Latitude protected_zone_latitude - Longitude protected_zone_longitude - -bool cen_dsrc_tolling_zone_id_is_present CenDsrcTollingZoneID cen_dsrc_tolling_zone_id - - - - - +bool cen_dsrc_tolling_zone_id_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg index 77134bbcd..55b9c5f22 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg @@ -26,20 +26,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ClosedLanes .extensible - -bool innerhard_shoulder_status_is_present HardShoulderStatus innerhard_shoulder_status +bool innerhard_shoulder_status_is_present - -bool outerhard_shoulder_status_is_present HardShoulderStatus outerhard_shoulder_status +bool outerhard_shoulder_status_is_present - -bool driving_lane_status_is_present DrivingLaneStatus driving_lane_status - - - - - +bool driving_lane_status_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg index df3412e0c..9181725da 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER CollisionRiskSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg index 1786b4977..6aead5fdf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Curvature - CurvatureValue curvature_value - CurvatureConfidence curvature_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg index 9d1974f26..3b87030fe 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg @@ -28,9 +28,8 @@ ## INTEGER CurvatureValue int16 value - int16 MIN = -1023 int16 MAX = 1023 - int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg index 0087d1183..85f1c120f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DENM - ItsPduHeader header - DecentralizedEnvironmentalNotificationMessage denm - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index beea5c8a1..d32f91b10 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER DangerousEndOfQueueSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg index 8a9140b26..9213942db 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg @@ -28,12 +28,12 @@ ## ENUMERATED DangerousGoodsBasic uint8 value -uint8 EXPLOSIVES1 = 0 -uint8 EXPLOSIVES2 = 1 -uint8 EXPLOSIVES3 = 2 -uint8 EXPLOSIVES4 = 3 -uint8 EXPLOSIVES5 = 4 -uint8 EXPLOSIVES6 = 5 +uint8 EXPLOSIVES_1 = 0 +uint8 EXPLOSIVES_2 = 1 +uint8 EXPLOSIVES_3 = 2 +uint8 EXPLOSIVES_4 = 3 +uint8 EXPLOSIVES_5 = 4 +uint8 EXPLOSIVES_6 = 5 uint8 FLAMMABLE_GASES = 6 uint8 NON_FLAMMABLE_GASES = 7 uint8 TOXIC_GASES = 8 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg index 4a38b0f84..cd1bbd0d9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg @@ -26,38 +26,28 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DangerousGoodsExtended .extensible - DangerousGoodsBasic dangerous_goods_type - uint16 un_number uint16 UN_NUMBER_MIN = 0 uint16 UN_NUMBER_MAX = 9999 bool elevated_temperature - bool tunnels_restricted - bool limited_quantity - -bool emergency_action_code_is_present string emergency_action_code +bool emergency_action_code_is_present uint8 EMERGENCY_ACTION_CODE_LENGTH_MIN = 1 uint8 EMERGENCY_ACTION_CODE_LENGTH_MAX = 24 -bool phone_number_is_present PhoneNumber phone_number +bool phone_number_is_present - -bool company_name_is_present string company_name +bool company_name_is_present uint8 COMPANY_NAME_LENGTH_MIN = 1 uint8 COMPANY_NAME_LENGTH_MAX = 24 - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg index ef126f527..fc81522ad 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER DangerousSituationSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 EMERGENCY_ELECTRONIC_BRAKE_ENGAGED = 1 uint8 PRE_CRASH_SYSTEM_ENGAGED = 2 @@ -40,3 +38,4 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg index f8f9ed8bd..885a7bf1b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg @@ -26,23 +26,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DecentralizedEnvironmentalNotificationMessage - ManagementContainer management - -bool situation_is_present SituationContainer situation +bool situation_is_present - -bool location_is_present LocationContainer location +bool location_is_present - -bool alacarte_is_present AlacarteContainer alacarte - - - - - +bool alacarte_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg index 5ee397cad..9e3df25b6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg @@ -28,10 +28,9 @@ ## INTEGER DeltaAltitude int16 value - int16 MIN = -12700 int16 MAX = 12800 - int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg index 561ca3b33..8a72373f9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg @@ -28,10 +28,9 @@ ## INTEGER DeltaLatitude int32 value - int32 MIN = -131071 int32 MAX = 131072 - int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg index 0b4a95b64..d32f293d9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg @@ -28,10 +28,9 @@ ## INTEGER DeltaLongitude int32 value - int32 MIN = -131071 int32 MAX = 131072 - int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg index 31a9f06dc..7ae8cd306 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg @@ -26,17 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE DeltaReferencePosition - DeltaLatitude delta_latitude - DeltaLongitude delta_longitude - DeltaAltitude delta_altitude - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg index c81f118e7..d521c7c58 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg @@ -30,6 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 - uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 88df9871d..5f1439a2d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -28,10 +28,9 @@ ## INTEGER EmergencyVehicleApproachingSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg index 591c76718..cd3856bf9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg @@ -30,7 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 7 - uint8 BIT_INDEX_HYDROGEN_STORAGE = 0 uint8 BIT_INDEX_ELECTRIC_ENERGY_STORAGE = 1 uint8 BIT_INDEX_LIQUID_PROPANE_GAS = 2 @@ -38,3 +37,4 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg index 1643fe007..c0fcc5bae 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg @@ -26,18 +26,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE EventPoint - DeltaReferencePosition event_position - -bool event_delta_time_is_present PathDeltaTime event_delta_time - +bool event_delta_time_is_present InformationQuality information_quality - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg index e865cb77d..d191062ca 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg @@ -30,7 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 8 - uint8 BIT_INDEX_LOW_BEAM_HEADLIGHTS_ON = 0 uint8 BIT_INDEX_HIGH_BEAM_HEADLIGHTS_ON = 1 uint8 BIT_INDEX_LEFT_TURN_SIGNAL_ON = 2 @@ -39,3 +38,4 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index ddbc580f8..c7b360731 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index 4d6e18d8c..63495337b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -28,13 +28,12 @@ ## INTEGER HazardousLocationDangerousCurveSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 DANGEROUS_LEFT_TURN_CURVE = 1 uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index 7b7221621..961c2dabb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 SHED_LOAD = 1 uint8 PARTS_OF_VEHICLES = 2 @@ -40,3 +38,4 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index e29146cd5..7aea67d58 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER HazardousLocationSurfaceConditionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 ROCKFALLS = 1 uint8 EARTHQUAKE_DAMAGE = 2 @@ -42,3 +40,4 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg index 95c48bc5f..961b9a6c6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Heading - HeadingValue heading_value - HeadingConfidence heading_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg index c8e97c562..378afb7c0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg @@ -28,11 +28,10 @@ ## INTEGER HeadingConfidence uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg index 4ead96652..22c0493e4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg @@ -28,12 +28,11 @@ ## INTEGER HeadingValue uint16 value - uint16 MIN = 0 uint16 MAX = 3601 - -uint16 WGS84_NORTH = 0 -uint16 WGS84_EAST = 900 -uint16 WGS84_SOUTH = 1800 -uint16 WGS84_WEST = 2700 +uint16 WGS_84_NORTH = 0 +uint16 WGS_84_EAST = 900 +uint16 WGS_84_SOUTH = 1800 +uint16 WGS_84_WEST = 2700 uint16 UNAVAILABLE = 3601 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg index 4041aa8cd..d5cfb65c4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg @@ -28,9 +28,8 @@ ## INTEGER HeightLonCarr uint8 value - uint8 MIN = 1 uint8 MAX = 100 - uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 317a4b8e0..6b69511e2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -28,11 +28,10 @@ ## INTEGER HumanPresenceOnTheRoadSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg index e5866377f..35e538c4b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg @@ -28,10 +28,9 @@ ## INTEGER HumanProblemSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg index e5c34ebc5..f0d813021 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg @@ -26,44 +26,27 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ImpactReductionContainer - HeightLonCarr height_lon_carr_left - HeightLonCarr height_lon_carr_right - PosLonCarr pos_lon_carr_left - PosLonCarr pos_lon_carr_right - PositionOfPillars position_of_pillars - PosCentMass pos_cent_mass - WheelBaseVehicle wheel_base_vehicle - TurningRadius turning_radius - PosFrontAx pos_front_ax - PositionOfOccupants position_of_occupants - VehicleMass vehicle_mass - RequestResponseIndication request_response_indication - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg index 7ac459b0f..43e2a2799 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg @@ -28,10 +28,9 @@ ## INTEGER InformationQuality uint8 value - uint8 MIN = 0 uint8 MAX = 7 - uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg index e0e95b0c5..b5c4b5740 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg @@ -26,7 +26,6 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ItsPduHeader - uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 uint8 PROTOCOL_VERSION_MAX = 255 @@ -48,10 +47,6 @@ uint8 MESSAGE_ID_EVCSN = 11 uint8 MESSAGE_ID_SAEM = 12 uint8 MESSAGE_ID_RTCMEM = 13 -StationID station_id - - - - +StationID station_id diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg index 2729a0deb..655869fa9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg @@ -28,11 +28,10 @@ ## INTEGER LanePosition int8 value - int8 MIN = -1 int8 MAX = 14 - int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg index a8afa582f..8a7b7678d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE LateralAcceleration - LateralAccelerationValue lateral_acceleration_value - AccelerationConfidence lateral_acceleration_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg index db9cf92b6..329b4a154 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg @@ -28,10 +28,9 @@ ## INTEGER LateralAccelerationValue int16 value - int16 MIN = -160 int16 MAX = 161 - int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg index 0b95abe96..918857d42 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg @@ -28,10 +28,9 @@ ## INTEGER Latitude int32 value - int32 MIN = -900000000 int32 MAX = 900000001 - int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg index 464b1bb86..d86ad6e16 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg @@ -30,6 +30,6 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 2 - uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg index 360c3f2f2..31fe73a21 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg @@ -26,23 +26,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE LocationContainer .extensible - -bool event_speed_is_present Speed event_speed +bool event_speed_is_present - -bool event_position_heading_is_present Heading event_position_heading - +bool event_position_heading_is_present Traces traces - -bool road_type_is_present RoadType road_type - - - - - +bool road_type_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg index 9f0bbac8b..21539c674 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg @@ -28,10 +28,9 @@ ## INTEGER Longitude int32 value - int32 MIN = -1800000000 int32 MAX = 1800000001 - int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg index 501b57fba..4880b8e99 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE LongitudinalAcceleration - LongitudinalAccelerationValue longitudinal_acceleration_value - AccelerationConfidence longitudinal_acceleration_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg index 90a6d1c80..30653502d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg @@ -28,10 +28,9 @@ ## INTEGER LongitudinalAccelerationValue int16 value - int16 MIN = -160 int16 MAX = 161 - int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg index 6fb21c3fb..13f77c76d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg @@ -26,43 +26,29 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ManagementContainer .extensible - ActionID action_id - TimestampIts detection_time - TimestampIts reference_time - -bool termination_is_present Termination termination - +bool termination_is_present ReferencePosition event_position - -bool relevance_distance_is_present RelevanceDistance relevance_distance +bool relevance_distance_is_present - -bool relevance_traffic_direction_is_present RelevanceTrafficDirection relevance_traffic_direction - +bool relevance_traffic_direction_is_present ValidityDuration validity_duration - -bool transmission_interval_is_present TransmissionInterval transmission_interval - +bool transmission_interval_is_present StationType station_type - - - uint32 VALIDITY_DURATION_DEFAULT = 600 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg index cba00ac08..7b2e01aa6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg @@ -28,9 +28,8 @@ ## INTEGER NumberOfOccupants uint8 value - uint8 MIN = 0 uint8 MAX = 127 - uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg index e07b00515..b5e9697e9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg @@ -28,8 +28,7 @@ ## INTEGER PathDeltaTime int64 value - int64 MIN = 1 int64 MAX = 65535 - int64 TEN_MILLI_SECONDS_IN_PAST = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg index 3a66f5c33..87ce1b575 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg @@ -26,15 +26,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PathPoint - DeltaReferencePosition path_position - -bool path_delta_time_is_present PathDeltaTime path_delta_time - - - - - +bool path_delta_time_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg index 84e9690d6..8cf5eeec5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg @@ -28,10 +28,9 @@ ## INTEGER PerformanceClass uint8 value - uint8 MIN = 0 uint8 MAX = 7 - uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg index a4e5238ff..1e9128d00 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg @@ -28,9 +28,8 @@ ## INTEGER PosCentMass uint8 value - uint8 MIN = 1 uint8 MAX = 63 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg index ebf822654..aeb665ecc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg @@ -26,17 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PosConfidenceEllipse - SemiAxisLength semi_major_confidence - SemiAxisLength semi_minor_confidence - HeadingValue semi_major_orientation - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg index bf9032811..606b67039 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg @@ -28,9 +28,8 @@ ## INTEGER PosFrontAx uint8 value - uint8 MIN = 1 uint8 MAX = 20 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg index 9b6643818..b01c3342b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg @@ -28,9 +28,8 @@ ## INTEGER PosLonCarr uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg index dea1c83a8..3f3cc73e9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg @@ -28,9 +28,8 @@ ## INTEGER PosPillar uint8 value - uint8 MIN = 1 uint8 MAX = 30 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg index 5320b5167..5837d8005 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg @@ -30,24 +30,24 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 20 +uint8 BIT_INDEX_ROW_1_LEFT_OCCUPIED = 0 +uint8 BIT_INDEX_ROW_1_RIGHT_OCCUPIED = 1 +uint8 BIT_INDEX_ROW_1_MID_OCCUPIED = 2 +uint8 BIT_INDEX_ROW_1_NOT_DETECTABLE = 3 +uint8 BIT_INDEX_ROW_1_NOT_PRESENT = 4 +uint8 BIT_INDEX_ROW_2_LEFT_OCCUPIED = 5 +uint8 BIT_INDEX_ROW_2_RIGHT_OCCUPIED = 6 +uint8 BIT_INDEX_ROW_2_MID_OCCUPIED = 7 +uint8 BIT_INDEX_ROW_2_NOT_DETECTABLE = 8 +uint8 BIT_INDEX_ROW_2_NOT_PRESENT = 9 +uint8 BIT_INDEX_ROW_3_LEFT_OCCUPIED = 10 +uint8 BIT_INDEX_ROW_3_RIGHT_OCCUPIED = 11 +uint8 BIT_INDEX_ROW_3_MID_OCCUPIED = 12 +uint8 BIT_INDEX_ROW_3_NOT_DETECTABLE = 13 +uint8 BIT_INDEX_ROW_3_NOT_PRESENT = 14 +uint8 BIT_INDEX_ROW_4_LEFT_OCCUPIED = 15 +uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 +uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 +uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 +uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 -uint8 BIT_INDEX_ROW1_LEFT_OCCUPIED = 0 -uint8 BIT_INDEX_ROW1_RIGHT_OCCUPIED = 1 -uint8 BIT_INDEX_ROW1_MID_OCCUPIED = 2 -uint8 BIT_INDEX_ROW1_NOT_DETECTABLE = 3 -uint8 BIT_INDEX_ROW1_NOT_PRESENT = 4 -uint8 BIT_INDEX_ROW2_LEFT_OCCUPIED = 5 -uint8 BIT_INDEX_ROW2_RIGHT_OCCUPIED = 6 -uint8 BIT_INDEX_ROW2_MID_OCCUPIED = 7 -uint8 BIT_INDEX_ROW2_NOT_DETECTABLE = 8 -uint8 BIT_INDEX_ROW2_NOT_PRESENT = 9 -uint8 BIT_INDEX_ROW3_LEFT_OCCUPIED = 10 -uint8 BIT_INDEX_ROW3_RIGHT_OCCUPIED = 11 -uint8 BIT_INDEX_ROW3_MID_OCCUPIED = 12 -uint8 BIT_INDEX_ROW3_NOT_DETECTABLE = 13 -uint8 BIT_INDEX_ROW3_NOT_PRESENT = 14 -uint8 BIT_INDEX_ROW4_LEFT_OCCUPIED = 15 -uint8 BIT_INDEX_ROW4_RIGHT_OCCUPIED = 16 -uint8 BIT_INDEX_ROW4_MID_OCCUPIED = 17 -uint8 BIT_INDEX_ROW4_NOT_DETECTABLE = 18 -uint8 BIT_INDEX_ROW4_NOT_PRESENT = 19 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg index 624da3885..8a1777231 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg @@ -28,12 +28,11 @@ ## INTEGER PostCrashSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg index 13bdb1cce..d8ac4b043 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg @@ -26,29 +26,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ProtectedCommunicationZone .extensible - ProtectedZoneType protected_zone_type - -bool expiry_time_is_present TimestampIts expiry_time - +bool expiry_time_is_present Latitude protected_zone_latitude - Longitude protected_zone_longitude - -bool protected_zone_radius_is_present ProtectedZoneRadius protected_zone_radius +bool protected_zone_radius_is_present - -bool protected_zone_id_is_present ProtectedZoneID protected_zone_id - - - - - +bool protected_zone_id_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg index 6597bca31..ae4c41709 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg @@ -28,7 +28,6 @@ ## INTEGER ProtectedZoneID uint32 value - uint32 MIN = 0 uint32 MAX = 134217727 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg index 2c685a0a7..e2a5a4e8e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg @@ -28,8 +28,7 @@ ## INTEGER ProtectedZoneRadius int64 value - int64 MIN = 1 int64 MAX = 255 - int64 ONE_METER = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg index ce76306de..f6fdbe3ea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE PtActivation - PtActivationType pt_activation_type - PtActivationData pt_activation_data - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg index 889884086..6a7a5bda6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg @@ -28,10 +28,9 @@ ## INTEGER PtActivationType uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNDEFINED_CODING_TYPE = 0 -uint8 R09_16_CODING_TYPE = 1 +uint8 R_09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg index dd647f7d2..07a4e8e6d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg @@ -26,20 +26,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE ReferencePosition - Latitude latitude - Longitude longitude - PosConfidenceEllipse position_confidence_ellipse - Altitude altitude - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg index 23fe60283..443ca5e6f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg @@ -28,12 +28,12 @@ ## ENUMERATED RelevanceDistance uint8 value -uint8 LESS_THAN50M = 0 -uint8 LESS_THAN100M = 1 -uint8 LESS_THAN200M = 2 -uint8 LESS_THAN500M = 3 -uint8 LESS_THAN1000M = 4 -uint8 LESS_THAN5KM = 5 -uint8 LESS_THAN10KM = 6 -uint8 OVER10KM = 7 +uint8 LESS_THAN_50M = 0 +uint8 LESS_THAN_100M = 1 +uint8 LESS_THAN_200M = 2 +uint8 LESS_THAN_500M = 3 +uint8 LESS_THAN_1000M = 4 +uint8 LESS_THAN_5KM = 5 +uint8 LESS_THAN_10KM = 6 +uint8 OVER_10KM = 7 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index 360516e4f..bd3a50097 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -28,13 +28,12 @@ ## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLES = 1 uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg index e99f6f67e..177df9da4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg @@ -26,44 +26,30 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE RoadWorksContainerExtended - -bool light_bar_siren_in_use_is_present LightBarSirenInUse light_bar_siren_in_use +bool light_bar_siren_in_use_is_present - -bool closed_lanes_is_present ClosedLanes closed_lanes +bool closed_lanes_is_present - -bool restriction_is_present RestrictedTypes restriction +bool restriction_is_present - -bool speed_limit_is_present SpeedLimit speed_limit +bool speed_limit_is_present - -bool incident_indication_is_present CauseCode incident_indication +bool incident_indication_is_present - -bool recommended_path_is_present ItineraryPath recommended_path +bool recommended_path_is_present - -bool starting_point_speed_limit_is_present DeltaReferencePosition starting_point_speed_limit +bool starting_point_speed_limit_is_present - -bool traffic_flow_rule_is_present TrafficRule traffic_flow_rule +bool traffic_flow_rule_is_present - -bool reference_denms_is_present ReferenceDenms reference_denms - - - - - +bool reference_denms_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg index 1c70e3429..b6575d73e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER RoadworksSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 MAJOR_ROADWORKS = 1 uint8 ROAD_MARKING_WORK = 2 @@ -39,3 +37,4 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg index 00570648c..eaa61cf9e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg @@ -28,10 +28,9 @@ ## INTEGER SemiAxisLength uint16 value - uint16 MIN = 0 uint16 MAX = 4095 - uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg index 46de8a045..27a36a32c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg @@ -28,7 +28,6 @@ ## INTEGER SequenceNumber uint16 value - uint16 MIN = 0 uint16 MAX = 65535 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg index 85cd4c570..0887a5941 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg @@ -28,11 +28,10 @@ ## INTEGER SignalViolationSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg index 002cb9eec..3b464a32c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg @@ -26,22 +26,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE SituationContainer .extensible - InformationQuality information_quality - CauseCode event_type - -bool linked_cause_is_present CauseCode linked_cause +bool linked_cause_is_present - -bool event_history_is_present EventHistory event_history - - - - - +bool event_history_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg index b2851a5dc..192a08311 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER SlowVehicleSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 MAINTENANCE_VEHICLE = 1 uint8 VEHICLES_SLOWING_TO_LOOK_AT_ACCIDENT = 2 @@ -41,3 +39,4 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg index 11895303b..743017c33 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg @@ -30,8 +30,8 @@ uint8[] value uint8 bits_unused uint8 SIZE_BITS = 4 - uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg index 23aef070f..f603b1dcc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE Speed - SpeedValue speed_value - SpeedConfidence speed_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg index 0b8c93e95..04391b581 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg @@ -28,11 +28,10 @@ ## INTEGER SpeedConfidence uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg index e71840559..b54a37c8a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg @@ -28,8 +28,7 @@ ## INTEGER SpeedLimit uint8 value - uint8 MIN = 1 uint8 MAX = 255 - uint8 ONE_KM_PER_HOUR = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg index f61585f55..15c55d7a2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg @@ -28,10 +28,9 @@ ## INTEGER SpeedValue uint16 value - uint16 MIN = 0 uint16 MAX = 16383 - uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg index 8b688adc3..9e5dc24dd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg @@ -28,7 +28,6 @@ ## INTEGER StationID uint32 value - uint32 MIN = 0 uint32 MAX = 4294967295 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg index 5674dcae4..08547aaa6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg @@ -28,10 +28,8 @@ ## INTEGER StationType uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNKNOWN = 0 uint8 PEDESTRIAN = 1 uint8 CYCLIST = 2 @@ -45,3 +43,4 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg index 1e851253c..a35450fd1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg @@ -28,8 +28,8 @@ ## ENUMERATED StationarySince uint8 value -uint8 LESS_THAN1_MINUTE = 0 -uint8 LESS_THAN2_MINUTES = 1 -uint8 LESS_THAN15_MINUTES = 2 -uint8 EQUAL_OR_GREATER15_MINUTES = 3 +uint8 LESS_THAN_1_MINUTE = 0 +uint8 LESS_THAN_2_MINUTES = 1 +uint8 LESS_THAN_15_MINUTES = 2 +uint8 EQUAL_OR_GREATER_15_MINUTES = 3 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg index 5d69a6db5..6e7d7fe65 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg @@ -26,32 +26,21 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE StationaryVehicleContainer - -bool stationary_since_is_present StationarySince stationary_since +bool stationary_since_is_present - -bool stationary_cause_is_present CauseCode stationary_cause +bool stationary_cause_is_present - -bool carrying_dangerous_goods_is_present DangerousGoodsExtended carrying_dangerous_goods +bool carrying_dangerous_goods_is_present - -bool number_of_occupants_is_present NumberOfOccupants number_of_occupants +bool number_of_occupants_is_present - -bool vehicle_identification_is_present VehicleIdentification vehicle_identification +bool vehicle_identification_is_present - -bool energy_storage_type_is_present EnergyStorageType energy_storage_type - - - - - +bool energy_storage_type_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg index adf013ce3..3b8bdb501 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -28,13 +28,12 @@ ## INTEGER StationaryVehicleSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 HUMAN_PROBLEM = 1 uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg index 7d033b9dd..b38f81f0d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE SteeringWheelAngle - SteeringWheelAngleValue steering_wheel_angle_value - SteeringWheelAngleConfidence steering_wheel_angle_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg index 836d42c04..c693654a8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg @@ -28,10 +28,9 @@ ## INTEGER SteeringWheelAngleConfidence uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg index afb11301f..2d6e2b766 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg @@ -28,11 +28,10 @@ ## INTEGER SteeringWheelAngleValue int16 value - int16 MIN = -511 int16 MAX = 512 - int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg index 76b818aae..305bb683a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg @@ -28,7 +28,6 @@ ## INTEGER SubCauseCodeType uint8 value - uint8 MIN = 0 uint8 MAX = 255 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg index 2259fe2cf..cc883d230 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg @@ -28,10 +28,9 @@ ## INTEGER Temperature int8 value - int8 MIN = -60 int8 MAX = 67 - -int8 EQUAL_OR_SMALLER_THAN_MINUS60_DEG = -60 +int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 int8 ONE_DEGREE_CELSIUS = 1 -int8 EQUAL_OR_GREATER_THAN67_DEG = 67 +int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg index 6ebee0fb7..d41d01815 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg @@ -28,9 +28,8 @@ ## INTEGER TimestampIts uint64 value - uint64 MIN = 0 uint64 MAX = 4398046511103 +uint64 UTC_START_OF_2004 = 0 +uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 -uint64 UTC_START_OF2004 = 0 -uint64 ONE_MILLISEC_AFTER_UTC_START_OF2004 = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg index 3bf2c7572..310a34eb7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER TrafficConditionSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 INCREASED_VOLUME_OF_TRAFFIC = 1 uint8 TRAFFIC_JAM_SLOWLY_INCREASING = 2 @@ -41,3 +39,4 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg index 76153c55f..6b411b09e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg @@ -28,9 +28,8 @@ ## INTEGER TransmissionInterval uint16 value - uint16 MIN = 1 uint16 MAX = 10000 - uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg index 7ca5596d8..50a96cf26 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg @@ -28,9 +28,8 @@ ## INTEGER TurningRadius uint8 value - uint8 MIN = 1 uint8 MAX = 255 - -uint8 POINT4_METERS = 1 +uint8 POINT_4_METERS = 1 uint8 UNAVAILABLE = 255 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg index 806532404..494e18e75 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg @@ -28,9 +28,8 @@ ## INTEGER ValidityDuration uint32 value - uint32 MIN = 0 uint32 MAX = 86400 - uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg index 79ed4c0b0..8ad8d31f5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -28,10 +28,8 @@ ## INTEGER VehicleBreakdownSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 LACK_OF_FUEL = 1 uint8 LACK_OF_BATTERY_POWER = 2 @@ -42,3 +40,4 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg index 73c04c673..ce86ece17 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg @@ -26,16 +26,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE VehicleIdentification .extensible - -bool w_m_inumber_is_present WMInumber w_m_inumber +bool w_m_inumber_is_present - -bool v_ds_is_present VDS v_ds - - - - - +bool v_ds_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg index 513a60967..0efac770f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE VehicleLength - VehicleLengthValue vehicle_length_value - VehicleLengthConfidenceIndication vehicle_length_confidence_indication - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg index 7e43bcf2c..c4136bc96 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg @@ -28,10 +28,9 @@ ## INTEGER VehicleLengthValue uint16 value - uint16 MIN = 1 uint16 MAX = 1023 - uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg index c8e936d57..f5895ca82 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg @@ -28,9 +28,8 @@ ## INTEGER VehicleMass uint16 value - uint16 MIN = 1 uint16 MAX = 1024 - uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg index d3a9a2c74..c8aac5c89 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg @@ -41,7 +41,7 @@ uint8 COMMERCIAL = 9 uint8 MILITARY = 10 uint8 ROAD_OPERATOR = 11 uint8 TAXI = 12 -uint8 RESERVED1 = 13 -uint8 RESERVED2 = 14 -uint8 RESERVED3 = 15 +uint8 RESERVED_1 = 13 +uint8 RESERVED_2 = 14 +uint8 RESERVED_3 = 15 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg index 575bb2893..c86ebc997 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg @@ -28,10 +28,9 @@ ## INTEGER VehicleWidth uint8 value - uint8 MIN = 1 uint8 MAX = 62 - uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg index 78515df4c..51e0d5979 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE VerticalAcceleration - VerticalAccelerationValue vertical_acceleration_value - AccelerationConfidence vertical_acceleration_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg index 20e71ad81..692493880 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg @@ -28,10 +28,9 @@ ## INTEGER VerticalAccelerationValue int16 value - int16 MIN = -160 int16 MAX = 161 - int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg index 77d9730b3..e8a16e042 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg @@ -28,9 +28,8 @@ ## INTEGER WheelBaseVehicle uint8 value - uint8 MIN = 1 uint8 MAX = 127 - uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg index 73b00caaf..df60cdcea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -28,10 +28,9 @@ ## INTEGER WrongWayDrivingSubCauseCode uint8 value - uint8 MIN = 0 uint8 MAX = 255 - uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg index 64e05f9a2..404b07465 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg @@ -26,14 +26,7 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- ## SEQUENCE YawRate - YawRateValue yaw_rate_value - YawRateConfidence yaw_rate_confidence - - - - - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg index 2a8dbc3e5..86fb2e26b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg @@ -28,11 +28,10 @@ ## INTEGER YawRateValue int16 value - int16 MIN = -32766 int16 MAX = 32767 - int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 + diff --git a/utils/codegen/codegen-rust/rgen/src/common/mod.rs b/utils/codegen/codegen-rust/rgen/src/common/mod.rs index 913897a44..8ca75a289 100644 --- a/utils/codegen/codegen-rust/rgen/src/common/mod.rs +++ b/utils/codegen/codegen-rust/rgen/src/common/mod.rs @@ -27,8 +27,9 @@ pub fn to_ros_snake_case(input: &str) -> String { while let Some(c) = peekable.next() { if c.is_lowercase() || c.is_numeric() { lowercase.push(c); - /* underscore before uppercase following a lowercase, aBx -> a_bx */ - if c != '_' && peekable.peek().map_or(false, |next| next.is_uppercase()) { + /* underscore before uppercase following a lowercase, aBx -> a_bx + * underscore before numeric following a lowercase, r09 -> r_09 */ + if c != '_' && peekable.peek().map_or(false, |next| next.is_uppercase() || !c.is_numeric() && next.is_numeric()) { lowercase.push('_'); } } else { diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs index b48ab1de9..37fd9926a 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs @@ -72,9 +72,9 @@ pub fn integer_template( licensed!(&format!( "## INTEGER {name}\n\ {comments}\n\ - {integer_type} value\n\n\ - {constraints}\n\n\ - {typed_dvalues}" + {integer_type} value\n\ + {constraints}\n\ + {typed_dvalues}\n" )) } @@ -95,8 +95,8 @@ pub fn bit_string_template(comments: &str, name: &str, constraints: &str, dvalue {comments}\n\ uint8[] value\n\ uint8 bits_unused\n\ - {constraints}\n\n\ - {typed_dvalues}" + {constraints}\n\ + {typed_dvalues}\n" )) } @@ -198,16 +198,21 @@ pub fn sequence_or_set_template( default_methods: &str, class_fields: &str, ) -> String { - licensed!(&format!( - "## SEQUENCE {name} {extensible}\n\ - {comments}\n\ - {members}\n\ - {}\n\ - {annotations}\n\ - {default_methods}\n\ - {class_fields}", - nested_members.join("\n") - )) + licensed!( + &vec![ + &format!("## SEQUENCE {name} {extensible}"), + comments, + members, + &nested_members.join("\n"), + annotations, + default_methods, + class_fields + ] + .into_iter() + .filter(|s| !s.is_empty()) + .collect::>() + .join("\n") + ) } pub fn sequence_or_set_of_template( @@ -254,13 +259,18 @@ pub fn choice_template( nested_options: Vec, annotations: &str, ) -> String { - licensed!(&format!( - "## CHOICE {name} {extensible}\n\ - {comments}\n\ - uint8 choice\n\n\ - {options}\n\ - {}\n\ - {annotations}", - nested_options.join("\n") - )) + licensed!( + &vec![ + &format!("## CHOICE {name} {extensible}"), + comments, + "uint8 choice\n", + options, + &nested_options.join("\n"), + annotations + ] + .into_iter() + .filter(|s| !s.is_empty()) + .collect::>() + .join("\n") + ) } diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs b/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs index cf0865cf9..bf65a0e24 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs @@ -219,23 +219,12 @@ pub fn format_sequence_or_set_members( sequence_or_set: &SequenceOrSet, parent_name: &String, ) -> Result { - let first_extension_index = sequence_or_set.extensible; sequence_or_set .members .iter() - .enumerate() - .try_fold("".to_string(), |mut acc, (i, m)| { - let extension_annotation = if i >= first_extension_index.unwrap_or(usize::MAX) - && m.name.starts_with("ext_group_") - { - "extension_addition_group".into() - } else if i >= first_extension_index.unwrap_or(usize::MAX) { - "quote!(extension_addition)".into() - } else { - "".into() - }; - format_sequence_member(m, parent_name, extension_annotation).map(|declaration| { - acc.push_str(&format!("{declaration}")); + .try_fold("".to_string(), |mut acc, m| { + format_sequence_member(m, parent_name).map(|declaration| { + acc.push_str(&format!("{declaration}\n\n")); acc }) }) @@ -244,7 +233,6 @@ pub fn format_sequence_or_set_members( fn format_sequence_member( member: &SequenceOrSetMember, parent_name: &String, - _extension_annotation: String, ) -> Result { let name = &member.name; let (mut all_constraints, mut formatted_type_name) = @@ -260,61 +248,61 @@ fn format_sequence_member( || member.name.starts_with("ext_group_") { formatted_type_name = format!( - "bool {name}_is_present\n\ - {formatted_type_name}" + "{formatted_type_name} {name}\n\ + bool {name}_is_present" ) + } else { + formatted_type_name = format!("{formatted_type_name} {name}") } - Ok(format!("{formatted_type_name} {name}\n\ - {formatted_constraints}\n\ - {distinguished_values}\n")) + + Ok( + vec![ + formatted_type_name, + formatted_constraints, + distinguished_values + ] + .into_iter() + .filter(|s| !s.is_empty()) + .collect::>() + .join("\n") + ) } pub fn format_choice_options( choice: &Choice, parent_name: &String, ) -> Result { - let first_extension_index = choice.extensible; let options = choice .options .iter() .enumerate() .map(|(i, o)| { - let extension_annotation = if i >= first_extension_index.unwrap_or(usize::MAX) - && o.name.starts_with("ext_group_") - { - "quote!(extension_addition_group)".into() - } else if i >= first_extension_index.unwrap_or(usize::MAX) { - "quote!(extension_addition)".into() - } else { - "".into() - }; - let name = o.name.clone(); - format_choice_option(name, o, parent_name, i, extension_annotation) + format_choice_option(o, parent_name, i) }) .collect::, _>>()?; let folded_options = options.iter().fold( - ("".to_string(), "".to_string()), - |mut acc, (declaration, valset)| { - acc.0.push_str(&format!("{declaration}\n")); - acc.1.push_str(&format!("{valset}\n")); + "".to_string(), + |mut acc, option| { + acc.push_str(&format!("{option}\n\n")); acc }, ); - Ok(format!("{}\n{}", folded_options.0, folded_options.1)) + Ok(folded_options) } fn format_choice_option( - name: String, member: &ChoiceOption, parent_name: &String, index: usize, - _extension_annotation: String, -) -> Result<(String, String), GeneratorError> { +) -> Result { let (_, formatted_type_name) = constraints_and_type_name(&member.ty, &member.name, parent_name)?; - let choice_type = format!("{formatted_type_name} {}", to_ros_snake_case(&name)); - let choice_selector = format!("uint8 CHOICE_{} = {index}", to_ros_const_case(&name)); - Ok((choice_type, choice_selector)) + let option = format!("{formatted_type_name} {}\n\ + uint8 CHOICE_{} = {index}", + to_ros_snake_case(&member.name), + to_ros_const_case(&member.name) + ); + Ok(option) } fn constraints_and_type_name( From 54cf6adcb807d07c720c4d0ea57d2577280d0264 Mon Sep 17 00:00:00 2001 From: v0-e Date: Thu, 6 Jun 2024 16:48:24 +0100 Subject: [PATCH 14/22] rgen: Further syntax-matching efforts with Python gen --- .../convertAccelerationConfidence.h | 2 - .../convertAccelerationControl.h | 2 - .../convertAccidentSubCauseCode.h | 2 - .../etsi_its_cam_conversion/convertActionID.h | 4 +- ...erseWeatherConditionAdhesionSubCauseCode.h | 2 - ...itionExtremeWeatherConditionSubCauseCode.h | 2 - ...eatherConditionPrecipitationSubCauseCode.h | 2 - ...seWeatherConditionVisibilitySubCauseCode.h | 2 - .../etsi_its_cam_conversion/convertAltitude.h | 2 - .../convertAltitudeConfidence.h | 2 - .../convertAltitudeValue.h | 2 - .../convertBasicContainer.h | 2 - ...onvertBasicVehicleContainerHighFrequency.h | 20 ++++----- ...convertBasicVehicleContainerLowFrequency.h | 2 - .../etsi_its_cam_conversion/convertCAM.h | 2 - .../convertCamParameters.h | 2 - .../convertCauseCode.h | 4 +- .../convertCauseCodeType.h | 2 - .../convertCenDsrcTollingZone.h | 2 - .../convertCenDsrcTollingZoneID.h | 2 - .../convertClosedLanes.h | 5 +-- .../convertCollisionRiskSubCauseCode.h | 2 - .../convertCoopAwareness.h | 2 - .../convertCurvature.h | 2 - .../convertCurvatureCalculationMode.h | 2 - .../convertCurvatureConfidence.h | 2 - .../convertCurvatureValue.h | 2 - .../convertDangerousEndOfQueueSubCauseCode.h | 2 - .../convertDangerousGoodsBasic.h | 2 - .../convertDangerousGoodsContainer.h | 2 - .../convertDangerousGoodsExtended.h | 16 +++---- .../convertDangerousSituationSubCauseCode.h | 2 - .../convertDeltaAltitude.h | 2 - .../convertDeltaLatitude.h | 2 - .../convertDeltaLongitude.h | 2 - .../convertDeltaReferencePosition.h | 4 +- .../convertDriveDirection.h | 2 - .../convertDrivingLaneStatus.h | 2 - .../convertEmbarkationStatus.h | 2 - .../convertEmergencyContainer.h | 2 - .../convertEmergencyPriority.h | 2 - ...tEmergencyVehicleApproachingSubCauseCode.h | 2 - .../convertEnergyStorageType.h | 2 - .../convertEventPoint.h | 4 +- .../convertExteriorLights.h | 2 - .../convertGenerationDeltaTime.h | 2 - .../convertHardShoulderStatus.h | 2 - ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 2 - ...ardousLocationDangerousCurveSubCauseCode.h | 2 - ...ousLocationObstacleOnTheRoadSubCauseCode.h | 2 - ...dousLocationSurfaceConditionSubCauseCode.h | 2 - .../etsi_its_cam_conversion/convertHeading.h | 4 +- .../convertHeadingConfidence.h | 2 - .../convertHeadingValue.h | 2 - .../convertHeightLonCarr.h | 2 - .../convertHighFrequencyContainer.h | 2 - ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 2 - .../convertHumanProblemSubCauseCode.h | 2 - .../convertInformationQuality.h | 2 - .../convertItsPduHeader.h | 4 -- .../convertLanePosition.h | 2 - .../convertLateralAcceleration.h | 4 +- .../convertLateralAccelerationValue.h | 2 - .../etsi_its_cam_conversion/convertLatitude.h | 2 - .../convertLightBarSirenInUse.h | 2 - .../convertLongitude.h | 2 - .../convertLongitudinalAcceleration.h | 4 +- .../convertLongitudinalAccelerationValue.h | 2 - .../convertLowFrequencyContainer.h | 2 - .../convertNumberOfOccupants.h | 2 - .../convertOpeningDaysHours.h | 2 - .../convertPathDeltaTime.h | 2 - .../convertPathPoint.h | 4 +- .../convertPerformanceClass.h | 2 - .../convertPhoneNumber.h | 2 - .../convertPosCentMass.h | 2 - .../convertPosConfidenceEllipse.h | 3 -- .../convertPosFrontAx.h | 2 - .../convertPosLonCarr.h | 2 - .../convertPosPillar.h | 2 - .../convertPositionOfOccupants.h | 2 - .../convertPositionOfPillars.h | 2 +- .../convertPositioningSolutionType.h | 2 - .../convertPostCrashSubCauseCode.h | 2 - .../convertProtectedCommunicationZone.h | 8 ++-- .../convertProtectedCommunicationZonesRSU.h | 2 +- .../convertProtectedZoneID.h | 2 - .../convertProtectedZoneRadius.h | 2 - .../convertProtectedZoneType.h | 2 - .../convertPtActivation.h | 2 - .../convertPtActivationData.h | 2 - .../convertPtActivationType.h | 2 - .../convertPublicTransportContainer.h | 2 - .../convertRSUContainerHighFrequency.h | 2 - .../convertReferencePosition.h | 4 +- .../convertRelevanceDistance.h | 2 - .../convertRelevanceTrafficDirection.h | 2 - .../convertRequestResponseIndication.h | 2 - ...cueAndRecoveryWorkInProgressSubCauseCode.h | 2 - .../convertRescueContainer.h | 2 - .../convertRestrictedTypes.h | 2 +- .../etsi_its_cam_conversion/convertRoadType.h | 2 - .../convertRoadWorksContainerBasic.h | 2 - .../convertRoadworksSubCauseCode.h | 2 - .../convertSafetyCarContainer.h | 6 +-- .../convertSemiAxisLength.h | 2 - .../convertSequenceNumber.h | 2 - .../convertSignalViolationSubCauseCode.h | 2 - .../convertSlowVehicleSubCauseCode.h | 2 - .../convertSpecialTransportContainer.h | 4 +- .../convertSpecialTransportType.h | 2 - .../convertSpecialVehicleContainer.h | 10 ++--- .../etsi_its_cam_conversion/convertSpeed.h | 4 +- .../convertSpeedConfidence.h | 2 - .../convertSpeedLimit.h | 2 - .../convertSpeedValue.h | 2 - .../convertStationID.h | 2 - .../convertStationType.h | 2 - .../convertStationarySince.h | 2 - .../convertStationaryVehicleSubCauseCode.h | 2 - .../convertSteeringWheelAngle.h | 4 +- .../convertSteeringWheelAngleConfidence.h | 2 - .../convertSteeringWheelAngleValue.h | 2 - .../convertSubCauseCodeType.h | 2 - .../convertTemperature.h | 2 - .../convertTimestampIts.h | 2 - .../etsi_its_cam_conversion/convertTraces.h | 2 +- .../convertTrafficConditionSubCauseCode.h | 2 - .../convertTrafficRule.h | 2 - .../convertTransmissionInterval.h | 2 - .../convertTurningRadius.h | 2 - .../etsi_its_cam_conversion/convertVDS.h | 2 - .../convertValidityDuration.h | 2 - .../convertVehicleBreakdownSubCauseCode.h | 2 - .../convertVehicleIdentification.h | 2 - .../convertVehicleLength.h | 4 +- ...convertVehicleLengthConfidenceIndication.h | 2 - .../convertVehicleLengthValue.h | 2 - .../convertVehicleMass.h | 2 - .../convertVehicleRole.h | 2 - .../convertVehicleWidth.h | 2 - .../convertVerticalAcceleration.h | 4 +- .../convertVerticalAccelerationValue.h | 2 - .../convertWMInumber.h | 2 - .../convertWheelBaseVehicle.h | 2 - .../convertWrongWayDrivingSubCauseCode.h | 2 - .../etsi_its_cam_conversion/convertYawRate.h | 4 +- .../convertYawRateConfidence.h | 2 - .../convertYawRateValue.h | 2 - .../convertAccelerationConfidence.h | 2 - .../convertAccelerationControl.h | 2 - .../convertAccidentSubCauseCode.h | 2 - .../convertActionID.h | 2 - ...erseWeatherConditionAdhesionSubCauseCode.h | 2 - ...itionExtremeWeatherConditionSubCauseCode.h | 2 - ...eatherConditionPrecipitationSubCauseCode.h | 2 - ...seWeatherConditionVisibilitySubCauseCode.h | 2 - .../convertAlacarteContainer.h | 6 +-- .../convertAltitude.h | 2 - .../convertAltitudeConfidence.h | 2 - .../convertAltitudeValue.h | 2 - .../convertCauseCode.h | 2 - .../convertCauseCodeType.h | 2 - .../convertCenDsrcTollingZone.h | 2 - .../convertCenDsrcTollingZoneID.h | 2 - .../convertClosedLanes.h | 3 -- .../convertCollisionRiskSubCauseCode.h | 2 - .../convertCurvature.h | 2 - .../convertCurvatureCalculationMode.h | 2 - .../convertCurvatureConfidence.h | 2 - .../convertCurvatureValue.h | 2 - .../etsi_its_denm_conversion/convertDENM.h | 2 - .../convertDangerousEndOfQueueSubCauseCode.h | 2 - .../convertDangerousGoodsBasic.h | 2 - .../convertDangerousGoodsExtended.h | 20 +++------ .../convertDangerousSituationSubCauseCode.h | 2 - ...tralizedEnvironmentalNotificationMessage.h | 2 - .../convertDeltaAltitude.h | 2 - .../convertDeltaLatitude.h | 2 - .../convertDeltaLongitude.h | 2 - .../convertDeltaReferencePosition.h | 6 +-- .../convertDriveDirection.h | 2 - .../convertDrivingLaneStatus.h | 2 - .../convertEmbarkationStatus.h | 2 - .../convertEmergencyPriority.h | 2 - ...tEmergencyVehicleApproachingSubCauseCode.h | 2 - .../convertEnergyStorageType.h | 2 - .../convertEventPoint.h | 6 +-- .../convertExteriorLights.h | 2 - .../convertHardShoulderStatus.h | 2 - ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 2 - ...ardousLocationDangerousCurveSubCauseCode.h | 2 - ...ousLocationObstacleOnTheRoadSubCauseCode.h | 2 - ...dousLocationSurfaceConditionSubCauseCode.h | 2 - .../etsi_its_denm_conversion/convertHeading.h | 4 +- .../convertHeadingConfidence.h | 2 - .../convertHeadingValue.h | 2 - .../convertHeightLonCarr.h | 2 - ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 2 - .../convertHumanProblemSubCauseCode.h | 2 - .../convertImpactReductionContainer.h | 14 +++--- .../convertInformationQuality.h | 2 - .../convertItineraryPath.h | 2 +- .../convertItsPduHeader.h | 4 -- .../convertLanePosition.h | 2 - .../convertLateralAcceleration.h | 4 +- .../convertLateralAccelerationValue.h | 2 - .../convertLatitude.h | 2 - .../convertLightBarSirenInUse.h | 2 - .../convertLocationContainer.h | 4 +- .../convertLongitude.h | 2 - .../convertLongitudinalAcceleration.h | 2 - .../convertLongitudinalAccelerationValue.h | 2 - .../convertManagementContainer.h | 13 +++--- .../convertNumberOfOccupants.h | 2 - .../convertOpeningDaysHours.h | 2 - .../convertPathDeltaTime.h | 2 - .../convertPathPoint.h | 4 +- .../convertPerformanceClass.h | 2 - .../convertPhoneNumber.h | 2 - .../convertPosCentMass.h | 2 - .../convertPosConfidenceEllipse.h | 3 -- .../convertPosFrontAx.h | 2 - .../convertPosLonCarr.h | 2 - .../convertPosPillar.h | 2 - .../convertPositionOfOccupants.h | 2 - .../convertPositioningSolutionType.h | 2 - .../convertPostCrashSubCauseCode.h | 2 - .../convertProtectedCommunicationZone.h | 8 ++-- .../convertProtectedZoneID.h | 2 - .../convertProtectedZoneRadius.h | 2 - .../convertProtectedZoneType.h | 2 - .../convertPtActivation.h | 4 +- .../convertPtActivationData.h | 2 - .../convertPtActivationType.h | 2 - .../convertReferencePosition.h | 6 +-- .../convertRelevanceDistance.h | 2 - .../convertRelevanceTrafficDirection.h | 2 - .../convertRequestResponseIndication.h | 2 - ...cueAndRecoveryWorkInProgressSubCauseCode.h | 2 - .../convertRoadType.h | 2 - .../convertRoadWorksContainerExtended.h | 12 +++-- .../convertRoadworksSubCauseCode.h | 2 - .../convertSemiAxisLength.h | 2 - .../convertSequenceNumber.h | 2 - .../convertSignalViolationSubCauseCode.h | 2 - .../convertSituationContainer.h | 3 -- .../convertSlowVehicleSubCauseCode.h | 2 - .../convertSpecialTransportType.h | 2 - .../etsi_its_denm_conversion/convertSpeed.h | 2 - .../convertSpeedConfidence.h | 2 - .../convertSpeedLimit.h | 2 - .../convertSpeedValue.h | 2 - .../convertStationID.h | 2 - .../convertStationType.h | 2 - .../convertStationarySince.h | 2 - .../convertStationaryVehicleContainer.h | 2 - .../convertStationaryVehicleSubCauseCode.h | 2 - .../convertSteeringWheelAngle.h | 4 +- .../convertSteeringWheelAngleConfidence.h | 2 - .../convertSteeringWheelAngleValue.h | 2 - .../convertSubCauseCodeType.h | 2 - .../convertTemperature.h | 2 - .../convertTermination.h | 2 - .../convertTimestampIts.h | 2 - .../etsi_its_denm_conversion/convertTraces.h | 2 +- .../convertTrafficConditionSubCauseCode.h | 2 - .../convertTrafficRule.h | 2 - .../convertTransmissionInterval.h | 2 - .../convertTurningRadius.h | 2 - .../etsi_its_denm_conversion/convertVDS.h | 2 - .../convertValidityDuration.h | 2 - .../convertVehicleBreakdownSubCauseCode.h | 2 - .../convertVehicleIdentification.h | 4 +- .../convertVehicleLength.h | 2 - ...convertVehicleLengthConfidenceIndication.h | 2 - .../convertVehicleLengthValue.h | 2 - .../convertVehicleMass.h | 2 - .../convertVehicleRole.h | 2 - .../convertVehicleWidth.h | 2 - .../convertVerticalAcceleration.h | 4 +- .../convertVerticalAccelerationValue.h | 2 - .../convertWMInumber.h | 2 - .../convertWheelBaseVehicle.h | 2 - .../convertWrongWayDrivingSubCauseCode.h | 2 - .../etsi_its_denm_conversion/convertYawRate.h | 2 - .../convertYawRateConfidence.h | 2 - .../convertYawRateValue.h | 2 - .../msg/AccelerationConfidence.msg | 1 - .../msg/AccelerationControl.msg | 1 - .../msg/AccidentSubCauseCode.msg | 1 - ...seWeatherConditionAdhesionSubCauseCode.msg | 1 - ...ionExtremeWeatherConditionSubCauseCode.msg | 1 - ...therConditionPrecipitationSubCauseCode.msg | 1 - ...WeatherConditionVisibilitySubCauseCode.msg | 1 - .../etsi_its_cam_msgs/msg/AltitudeValue.msg | 1 - .../etsi_its_cam_msgs/msg/CauseCodeType.msg | 1 - .../msg/CollisionRiskSubCauseCode.msg | 1 - .../etsi_its_cam_msgs/msg/CurvatureValue.msg | 1 - .../msg/DangerousEndOfQueueSubCauseCode.msg | 1 - .../msg/DangerousGoodsExtended.msg | 8 ++-- .../msg/DangerousSituationSubCauseCode.msg | 1 - .../etsi_its_cam_msgs/msg/DeltaAltitude.msg | 1 - .../etsi_its_cam_msgs/msg/DeltaLatitude.msg | 1 - .../etsi_its_cam_msgs/msg/DeltaLongitude.msg | 1 - .../etsi_its_cam_msgs/msg/DigitalMap.msg | 4 +- .../msg/DrivingLaneStatus.msg | 4 +- .../msg/EmergencyPriority.msg | 1 - ...mergencyVehicleApproachingSubCauseCode.msg | 1 - .../msg/EnergyStorageType.msg | 1 - .../etsi_its_cam_msgs/msg/EventHistory.msg | 4 +- .../etsi_its_cam_msgs/msg/ExteriorLights.msg | 1 - .../msg/GenerationDeltaTime.msg | 1 - ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 1 - ...dousLocationDangerousCurveSubCauseCode.msg | 1 - ...sLocationObstacleOnTheRoadSubCauseCode.msg | 1 - ...usLocationSurfaceConditionSubCauseCode.msg | 1 - .../msg/HeadingConfidence.msg | 1 - .../etsi_its_cam_msgs/msg/HeadingValue.msg | 1 - .../etsi_its_cam_msgs/msg/HeightLonCarr.msg | 1 - .../HumanPresenceOnTheRoadSubCauseCode.msg | 1 - .../msg/HumanProblemSubCauseCode.msg | 1 - .../msg/InformationQuality.msg | 1 - .../etsi_its_cam_msgs/msg/ItineraryPath.msg | 4 +- .../etsi_its_cam_msgs/msg/ItsPduHeader.msg | 1 - .../etsi_its_cam_msgs/msg/LanePosition.msg | 1 - .../msg/LateralAccelerationValue.msg | 1 - .../etsi_its_cam_msgs/msg/Latitude.msg | 1 - .../msg/LightBarSirenInUse.msg | 1 - .../etsi_its_cam_msgs/msg/Longitude.msg | 1 - .../msg/LongitudinalAccelerationValue.msg | 1 - .../msg/NumberOfOccupants.msg | 1 - .../etsi_its_cam_msgs/msg/PathDeltaTime.msg | 1 - .../etsi_its_cam_msgs/msg/PathHistory.msg | 4 +- .../msg/PerformanceClass.msg | 1 - .../etsi_its_cam_msgs/msg/PosCentMass.msg | 1 - .../etsi_its_cam_msgs/msg/PosFrontAx.msg | 1 - .../etsi_its_cam_msgs/msg/PosLonCarr.msg | 1 - .../etsi_its_cam_msgs/msg/PosPillar.msg | 1 - .../msg/PositionOfOccupants.msg | 1 - .../msg/PositionOfPillars.msg | 4 +- .../msg/PostCrashSubCauseCode.msg | 1 - .../msg/ProtectedCommunicationZonesRSU.msg | 4 +- .../msg/ProtectedZoneRadius.msg | 1 - .../msg/PtActivationType.msg | 1 - ...eAndRecoveryWorkInProgressSubCauseCode.msg | 1 - .../etsi_its_cam_msgs/msg/RestrictedTypes.msg | 4 +- .../msg/RoadworksSubCauseCode.msg | 1 - .../etsi_its_cam_msgs/msg/SemiAxisLength.msg | 1 - .../msg/SignalViolationSubCauseCode.msg | 1 - .../msg/SlowVehicleSubCauseCode.msg | 1 - .../msg/SpecialTransportType.msg | 1 - .../etsi_its_cam_msgs/msg/SpeedConfidence.msg | 1 - .../etsi_its_cam_msgs/msg/SpeedLimit.msg | 1 - .../etsi_its_cam_msgs/msg/SpeedValue.msg | 1 - .../etsi_its_cam_msgs/msg/StationType.msg | 1 - .../msg/StationaryVehicleSubCauseCode.msg | 1 - .../msg/SteeringWheelAngleConfidence.msg | 1 - .../msg/SteeringWheelAngleValue.msg | 1 - .../etsi_its_cam_msgs/msg/Temperature.msg | 1 - .../etsi_its_cam_msgs/msg/TimestampIts.msg | 1 - .../etsi_its_cam_msgs/msg/Traces.msg | 4 +- .../msg/TrafficConditionSubCauseCode.msg | 1 - .../msg/TransmissionInterval.msg | 1 - .../etsi_its_cam_msgs/msg/TurningRadius.msg | 1 - .../msg/ValidityDuration.msg | 1 - .../msg/VehicleBreakdownSubCauseCode.msg | 1 - .../msg/VehicleLengthValue.msg | 1 - .../etsi_its_cam_msgs/msg/VehicleMass.msg | 1 - .../etsi_its_cam_msgs/msg/VehicleWidth.msg | 1 - .../msg/VerticalAccelerationValue.msg | 1 - .../msg/WheelBaseVehicle.msg | 1 - .../msg/WrongWayDrivingSubCauseCode.msg | 1 - .../etsi_its_cam_msgs/msg/YawRateValue.msg | 1 - .../msg/AccelerationConfidence.msg | 1 - .../msg/AccelerationControl.msg | 1 - .../msg/AccidentSubCauseCode.msg | 1 - ...seWeatherConditionAdhesionSubCauseCode.msg | 1 - ...ionExtremeWeatherConditionSubCauseCode.msg | 1 - ...therConditionPrecipitationSubCauseCode.msg | 1 - ...WeatherConditionVisibilitySubCauseCode.msg | 1 - .../etsi_its_denm_msgs/msg/AltitudeValue.msg | 1 - .../etsi_its_denm_msgs/msg/CauseCodeType.msg | 1 - .../msg/CollisionRiskSubCauseCode.msg | 1 - .../etsi_its_denm_msgs/msg/CurvatureValue.msg | 1 - .../msg/DangerousEndOfQueueSubCauseCode.msg | 1 - .../msg/DangerousGoodsExtended.msg | 8 ++-- .../msg/DangerousSituationSubCauseCode.msg | 1 - .../etsi_its_denm_msgs/msg/DeltaAltitude.msg | 1 - .../etsi_its_denm_msgs/msg/DeltaLatitude.msg | 1 - .../etsi_its_denm_msgs/msg/DeltaLongitude.msg | 1 - .../etsi_its_denm_msgs/msg/DigitalMap.msg | 4 +- .../msg/DrivingLaneStatus.msg | 4 +- .../msg/EmergencyPriority.msg | 1 - ...mergencyVehicleApproachingSubCauseCode.msg | 1 - .../msg/EnergyStorageType.msg | 1 - .../etsi_its_denm_msgs/msg/EventHistory.msg | 4 +- .../etsi_its_denm_msgs/msg/ExteriorLights.msg | 1 - ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 1 - ...dousLocationDangerousCurveSubCauseCode.msg | 1 - ...sLocationObstacleOnTheRoadSubCauseCode.msg | 1 - ...usLocationSurfaceConditionSubCauseCode.msg | 1 - .../msg/HeadingConfidence.msg | 1 - .../etsi_its_denm_msgs/msg/HeadingValue.msg | 1 - .../etsi_its_denm_msgs/msg/HeightLonCarr.msg | 1 - .../HumanPresenceOnTheRoadSubCauseCode.msg | 1 - .../msg/HumanProblemSubCauseCode.msg | 1 - .../msg/InformationQuality.msg | 1 - .../etsi_its_denm_msgs/msg/ItineraryPath.msg | 4 +- .../etsi_its_denm_msgs/msg/ItsPduHeader.msg | 1 - .../etsi_its_denm_msgs/msg/LanePosition.msg | 1 - .../msg/LateralAccelerationValue.msg | 1 - .../etsi_its_denm_msgs/msg/Latitude.msg | 1 - .../msg/LightBarSirenInUse.msg | 1 - .../etsi_its_denm_msgs/msg/Longitude.msg | 1 - .../msg/LongitudinalAccelerationValue.msg | 1 - .../msg/NumberOfOccupants.msg | 1 - .../etsi_its_denm_msgs/msg/PathDeltaTime.msg | 1 - .../etsi_its_denm_msgs/msg/PathHistory.msg | 4 +- .../msg/PerformanceClass.msg | 1 - .../etsi_its_denm_msgs/msg/PosCentMass.msg | 1 - .../etsi_its_denm_msgs/msg/PosFrontAx.msg | 1 - .../etsi_its_denm_msgs/msg/PosLonCarr.msg | 1 - .../etsi_its_denm_msgs/msg/PosPillar.msg | 1 - .../msg/PositionOfOccupants.msg | 1 - .../msg/PositionOfPillars.msg | 4 +- .../msg/PostCrashSubCauseCode.msg | 1 - .../msg/ProtectedCommunicationZonesRSU.msg | 4 +- .../msg/ProtectedZoneRadius.msg | 1 - .../msg/PtActivationType.msg | 1 - .../etsi_its_denm_msgs/msg/ReferenceDenms.msg | 4 +- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 1 - .../msg/RestrictedTypes.msg | 4 +- .../msg/RoadworksSubCauseCode.msg | 1 - .../etsi_its_denm_msgs/msg/SemiAxisLength.msg | 1 - .../msg/SignalViolationSubCauseCode.msg | 1 - .../msg/SlowVehicleSubCauseCode.msg | 1 - .../msg/SpecialTransportType.msg | 1 - .../msg/SpeedConfidence.msg | 1 - .../etsi_its_denm_msgs/msg/SpeedLimit.msg | 1 - .../etsi_its_denm_msgs/msg/SpeedValue.msg | 1 - .../etsi_its_denm_msgs/msg/StationType.msg | 1 - .../msg/StationaryVehicleSubCauseCode.msg | 1 - .../msg/SteeringWheelAngleConfidence.msg | 1 - .../msg/SteeringWheelAngleValue.msg | 1 - .../etsi_its_denm_msgs/msg/Temperature.msg | 1 - .../etsi_its_denm_msgs/msg/TimestampIts.msg | 1 - .../etsi_its_denm_msgs/msg/Traces.msg | 4 +- .../msg/TrafficConditionSubCauseCode.msg | 1 - .../msg/TransmissionInterval.msg | 1 - .../etsi_its_denm_msgs/msg/TurningRadius.msg | 1 - .../msg/ValidityDuration.msg | 1 - .../msg/VehicleBreakdownSubCauseCode.msg | 1 - .../msg/VehicleLengthValue.msg | 1 - .../etsi_its_denm_msgs/msg/VehicleMass.msg | 1 - .../etsi_its_denm_msgs/msg/VehicleWidth.msg | 1 - .../msg/VerticalAccelerationValue.msg | 1 - .../msg/WheelBaseVehicle.msg | 1 - .../msg/WrongWayDrivingSubCauseCode.msg | 1 - .../etsi_its_denm_msgs/msg/YawRateValue.msg | 1 - .../rgen/src/conversion/template.rs | 27 ++++++++++-- .../codegen-rust/rgen/src/msgs/builder.rs | 2 +- .../codegen-rust/rgen/src/msgs/template.rs | 2 +- .../codegen-rust/rgen/src/msgs/utils.rs | 44 ++++++++++--------- 464 files changed, 181 insertions(+), 893 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h index 7b030b752..53e40b3ee 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h index 9302ae5d3..fc5aa8cbd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h index 27eff85a6..e293a6a81 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index cec2204d6..50b350be1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index 9e485879b..e0b1b0cc2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 4f6e63b95..0c6c6e521 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index de6f3d23a..4c7bcaffb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index fb7a3bc2b..be4ec702b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index f61a38ec1..b6ef74fe8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h index c6bc772fc..6e618a11e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h index eb00d72eb..38b5c3703 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index 5e6b1ed14..10ad0ce93 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index 41d225fb5..0118add42 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -30,25 +30,23 @@ SOFTWARE. #pragma once -#include - #include -#include +#include #include #include -#include -#include +#include #include -#include #include -#include -#include +#include +#include +#include #include -#include -#include -#include #include +#include +#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index fcd810c89..7b861e103 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index e4761658c..45ad11a31 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -31,8 +31,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index 8f9d41621..6982fd8cd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h index d74d4ccab..63cad738f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h index 25907cb56..453ea9439 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index b24c52f2a..7f779c747 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h index 3c683ca71..51cafb799 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h index 656b774d1..93e235361 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h @@ -30,12 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h index 16a6a376b..89f8d13e0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h index cebee1234..05183a579 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 38661d85c..3e4ae6382 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h index 28b587f94..d6988a4f9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h index 10ba44b3d..60e133423 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h index 4db3ea455..94d2f57b0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h index 92156d78c..c48ea0369 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h index c74c9031b..6366b41b6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h index e2a1e5490..da54b42af 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index d05102754..f1733605b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -30,23 +30,17 @@ SOFTWARE. #pragma once -#include - #include +#include +#include +#include +#include #include #include #include -#include -#include -#include -#include -#include -#include +#include #include #include -#include -#include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h index bf3f1e578..0ac42edf3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h index 5232bd2fe..ae5d90d46 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h index 24158960f..9b4d2da4f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h index f4283eb46..09d16fbfb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index 1f193cdf9..2e2590d87 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -30,12 +30,10 @@ SOFTWARE. #pragma once -#include - #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h index 63979f9ae..cc5f20df3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h index bcdc23013..213ab8ee6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h index 3983d8430..a09f47d99 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index cc7ce1df0..687e41aeb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h index 6e69d1bbd..175e7e63f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 046d1a30c..3ae1c7e7e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h index e1ed497e2..fbb0d1c71 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index 8a2715274..43fd203f1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h index 575ae5277..3bd9655c0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h index 9eb24d457..c28c7cf77 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h index 2344246d3..2dd8a4417 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 57011e4d5..cb58cbb60 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index 7132ef1ee..b95fd2f20 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index dcec4c5f8..d4a5af23a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 42d6b4953..9220c1a4a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index 1ba8f3432..b99a2db20 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h index 41fe903af..9c8d4f5b5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h index 83c390fd7..53ccd4c10 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h index 7ce7f767e..8eba5cc41 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h index 07b06c21c..d6da1fc9f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index ba486b78b..d7c69c507 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h index 10b7f0e98..ff6f3cb1d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h index 48ebe0f7e..993d5484f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h index 1546f7625..1987e268a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h @@ -30,13 +30,9 @@ SOFTWARE. #pragma once -#include - #include #include #include -#include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h index 610209b25..e17697960 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index ecaee5dcb..53f8fb9a3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h index df6214dc7..842650580 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h index fd012b405..484c17f3c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h index 39427bf6d..01ad51b0c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h index e459673dd..45d06a556 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h index 2988eacdd..73af8acaa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h index aef7329e9..b282e4c8a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h index ac9a953e6..40ef0d5c2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h index 16c479fda..a494b2680 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h index 896b2dfe3..9201690dd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h index 91757738d..e474ed740 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index 30403c61e..742cf85c0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h index 8d846643f..e59256c2a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h index 181ff03c1..c0df7132d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h index 7355ca2fa..d105f9ebd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index 7321483bf..26dd633dc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -30,11 +30,8 @@ SOFTWARE. #pragma once -#include - #include #include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h index 5323f1d1d..d2b282bbb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h index 7fb9b07d0..ed3ec6f33 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h index 08073d045..1b8818ebf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h index f11feb925..9a3079bd2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 67344e0bf..71cd8e11f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h index 8e105535a..6b47bea15 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h index 5a683ba5b..7ed80d1fc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index fb6d4f47c..8233ff8a2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -30,15 +30,13 @@ SOFTWARE. #pragma once -#include - #include +#include +#include +#include #include #include #include -#include -#include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index c03d39f8c..a9add2322 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h index c611e7cc4..52977161e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h index b9f35617d..dc894c2c0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h index 91273f25f..26e7d8955 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index 782394911..92ba34eb8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h index 747efe100..1196423d2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h index 6e89e9230..1365dd16b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index f2cb3fa96..79be970e7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h index b9a03bb1c..72c932aa6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index 763f96dec..e8ccd6335 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -30,12 +30,10 @@ SOFTWARE. #pragma once -#include - #include -#include #include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h index 94905185a..fe02f7977 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h index c9ca4e9ac..531ae9eb9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h index 2ef8acc52..2ebaf1630 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index 708f2ef75..092e472c4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h index 887b58e3d..c533d691d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index c339b6461..28695a91b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h index 2fda3dbf6..ecb66b71e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index d97381053..769751073 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h index 0013668cf..55d4c0d6a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index 95759f363..89e1e1c9d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -30,13 +30,11 @@ SOFTWARE. #pragma once -#include - #include -#include -#include #include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h index d2aa1b1ef..c50816c7d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h index 6f629a380..fe596af03 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h index 75b0d6b31..308321ef4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h index d023ca480..897ea247a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h index 09e5c2124..86254dc81 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h index a48408e6f..2a59c08d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index 121c0b96d..b975a8cb8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -30,16 +30,14 @@ SOFTWARE. #pragma once -#include - #include -#include -#include -#include -#include #include +#include +#include #include +#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index b815908ec..31df3720c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h index 60cf49e9c..c0ee1cd39 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h index 64017e72d..8e6253b1e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h index 3392b338e..fdce06cc7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h index 4e267a466..2b939e9ab 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h index 7807999e8..c10e555e2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h index 9bc7ff50a..20695cccf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h index 6f2dbe531..9a3585a07 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index 910737ea9..86f948e53 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h index 7fe66af04..5bda9ff13 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h index 155de1eff..557ece0bc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h index 691e51eac..f51866a5e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h index 381676751..18f02776d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h index 37e5f64b7..0cca9fbc6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index c95eb4a23..f5c40515c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h index d1e5be3df..e7b79d726 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h index 5ac173b6f..80eab4581 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h index ff33d1bc7..679934de0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h index 1c023aa0a..352ca56a5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h index 59171475a..726686d78 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h index 79527f32d..aeda8ca93 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h index 3bd117634..d7cf4f7a9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index 3e044b8cf..2a7863712 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index 49e5b5717..0e941105e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h index d8d6aa84e..39c7128e5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h index cb30ef81b..a577dc92a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h index 7f0793218..b16d9a03e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h index 8beeb695c..5937bba66 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h index 889655cd1..67d9eb129 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index 84e432f70..12ebeb807 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h index 2f4bad71a..6eddf9109 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h index fc9b63ab8..68d80eb8f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h index abfcdf582..288b35fc7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h index ea2f7164c..f642eae93 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index 8999ef7aa..c8a04980a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h index e247da1ec..d1ae9a21d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h index fdc50241c..30d975955 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h index 901e832b7..284acdc84 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h index 7890f3fc8..7869a4434 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h index 87989b902..039001720 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index 4fd28f1f2..45591a1aa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index 4e3b48d04..e2e243c51 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 092e98fc0..1035ff79d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index ae36ae449..7e41ff671 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index 94bfc6ef6..2260f2908 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 816a4ece2..60c16d0e7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -30,15 +30,13 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index 794c648bb..9906518a7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h index 072bd869c..9224e1c5c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h index 1ca200eec..83a07854f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index 99bb2054f..6e96d65b2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h index ecb2a446b..0c7b2144b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 4ecad1ee7..75eaeb9b8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h index f3bdc5d57..bd4c7c5a3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index 19d0b04dd..3dae358b2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -30,11 +30,8 @@ SOFTWARE. #pragma once -#include - #include #include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h index 024c39ba0..32c2fea9b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index f4ff874a5..14d97441a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h index 15a6c9bdb..20bd6caef 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h index fb8d9e348..1999a1911 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h index c7443b024..c01039d5c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h index fd852655b..1f50131f4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h index 2a2879ae4..f8e43bab1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h index dc0ae4d92..e0eb10ec2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index a7a5fc68d..acdc50b5a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -30,23 +30,17 @@ SOFTWARE. #pragma once -#include - #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include #include #include #include +#include +#include +#include +#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h index aa11170c2..18097be83 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index 36b3d10f8..c6d8ad131 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h index 1f2e84942..cffb6919f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h index b26897317..f3a7e4aa1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h index 99316b425..859ee40b6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index f9b540e25..aca38b575 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -30,12 +30,10 @@ SOFTWARE. #pragma once -#include - #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h index 31ff44f0b..d7d8960d9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h index 3faee3a8d..7817d63fa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h index 21ae660a1..0c733f2af 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h index f620e0d5c..eecb38ae2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 046cfd300..dfa956d00 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h index 5ca43ee7c..bf45eb88b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index 0f85c124b..28a476e1c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -30,12 +30,10 @@ SOFTWARE. #pragma once -#include - #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h index f0d5d886f..60eadeed6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h index ded15fd94..d19b4d4fe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index bfec27339..93fb07f64 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index 2913c2de3..b7d4f5b73 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index f1647b5b0..bdb5e5b52 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index ee028a10b..394f524aa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index 506b5cdf0..7d471774e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h index 803e12b8d..56fc14857 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h index 96f24ed3c..36ea78709 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h index 8f989eec2..59cc9045e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index 18efa87bc..237e4937d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h index a718b2f22..b57002c7f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index e18c9f739..211d25efe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -30,21 +30,17 @@ SOFTWARE. #pragma once -#include - #include -#include -#include -#include -#include #include +#include +#include #include +#include #include -#include +#include #include #include -#include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h index b1dc672a9..d834c3135 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index 952e35f8d..efa1f46ee 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index 9f649ef92..49ebcd336 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -30,13 +30,9 @@ SOFTWARE. #pragma once -#include - #include #include #include -#include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h index 3f9544da7..56311d2dd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h index c474de0e4..f3c9cf7f5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h index ae8b3a7d7..322c34dd5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h index 3bde306af..0492e5d1c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h index 7efcb8da8..f220f7748 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index 613c02eaf..3c026f8ec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -30,13 +30,11 @@ SOFTWARE. #pragma once -#include - #include -#include #include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h index 3851a606b..8e1c86666 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index 1817552c3..a86ad5492 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h index 4d3fd466f..a8785c950 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index 72ef6b524..c930fb4cb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -30,19 +30,16 @@ SOFTWARE. #pragma once -#include - #include -#include -#include +#include +#include #include +#include #include -#include -#include #include -#include +#include #include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h index de7a171b4..7cbade254 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h index 1ae6b276b..4e2955db8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h index 9eabf099f..d21139adc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index 0415c1981..0b0d41e8c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h index 92ecf0a33..500f259d7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h index f68edf9cc..27f41f14f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h index ae82f1a25..6b67b6541 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index b2a40c790..531e91143 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -30,11 +30,8 @@ SOFTWARE. #pragma once -#include - #include #include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h index 46034f602..4df52b4b2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h index d2d9e9337..6ba9fc856 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h index e7036d39f..26e242863 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h index 76b61688b..00096bb86 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h index ce9fc6881..18bc206b3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h index 51f4f905d..4aeb342d9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index 1b5a2c30b..4faad85e7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -30,14 +30,12 @@ SOFTWARE. #pragma once -#include - #include -#include #include -#include -#include #include +#include +#include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h index de7cc6f58..abdffe796 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h index 165d46ba0..82aa80137 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h index f9994d328..dfa7ebde9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index bf7b38560..83b8161b6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h index c1cbc351e..4ab3c185d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h index 33670b88e..f8a372d80 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index 4cfa8e350..90659a91e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -30,13 +30,11 @@ SOFTWARE. #pragma once -#include - #include #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h index 8ef44bd15..87f2914bd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h index 16e64825a..67ea2d4ba 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h index 522e1584e..68f8b3b55 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index 4eca8b072..b4a03f33d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h index 9ba9199de..692b8d147 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index efded5c7f..2a92db99b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -30,18 +30,16 @@ SOFTWARE. #pragma once -#include - #include -#include +#include #include -#include +#include +#include #include +#include +#include #include -#include -#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h index 158b4abf2..e1f254b4c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h index ce7670dd5..8b9dcc981 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h index 6a4d528f7..35de83560 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h index 5e8a4b1ee..6d272841c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index ca6cf3868..20be3177f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -30,12 +30,9 @@ SOFTWARE. #pragma once -#include - #include #include #include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h index d5ec3203b..a21c918f9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h index 03cef559e..322cc4c2f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index 8266a1e48..2cc992f2a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h index a02d4f4fc..e40813fe9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h index 533927a6f..15ac2bd75 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h index 7b2286540..72394204e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h index 91cccf075..64e8d6287 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h index 83cd3c3c5..a67937635 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h index a8d818959..4e66545dc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 006516075..eec23d213 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h index c839d4cd7..627a11ca9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index 86a1e1e24..9d5276877 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h index a81e299b7..c4d44243d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h index 497fc9709..33048b3c7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h index 274a5ff94..0a13246d7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h index fa3c0a635..acb7ce1ca 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h index e229bb851..a55ce6f5e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h index 53765cb1a..00687d428 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 7eadf0db7..4ce923012 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h index cb9a641c1..7aa657675 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h index 65613fa59..55c3e6634 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h index c59b0b62a..bb0c73e8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h index a5f3e0449..904877c90 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h index b9a24ee6c..a73207bce 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h index dfe95cb8d..8d2de77ce 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h index 7c348ba80..f24915c47 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index 7a66815d4..7d768e433 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index f74d0c0fe..8e46738fb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h index 3e6662652..a33571cd8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h index 5f56f9e3d..cd80ddc8e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h index 2464c99fa..2043cf65a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h index 6d5576192..986ad3af1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h index 4b1810d72..a7e54eaab 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index de677823e..9c6593ad6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -30,11 +30,9 @@ SOFTWARE. #pragma once -#include - #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h index 4eb52b0e7..bea5bf0c1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h index 7921d88d6..2d17434fe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h index 4c00ede7e..1f1009943 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h index 1a4e9ab81..0efc0041d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h index 185c0e637..fede6836a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h index 4391e50ec..693113711 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h index 0583dbb92..0e7b9f975 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h @@ -30,8 +30,6 @@ SOFTWARE. #pragma once -#include - #include #include #include diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg index f01b8f344..2c96c29bd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg @@ -33,4 +33,3 @@ uint8 MAX = 102 uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg index 8a147710d..59891bb3a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg @@ -37,4 +37,3 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg index 17db3e428..2e85a1965 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg @@ -39,4 +39,3 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 08ca22f25..4d5baa2ef 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -41,4 +41,3 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index bd619386f..a45f41e0f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -37,4 +37,3 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index ec4889e8f..afe120d54 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -34,4 +34,3 @@ uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 512dbd14a..84b13bbde 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -39,4 +39,3 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg index c804dadb1..4dbc604e6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg @@ -33,4 +33,3 @@ int32 MAX = 800001 int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg index 0db806cca..61c553d96 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg @@ -57,4 +57,3 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg index 9181725da..a1439f329 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg index 3b87030fe..1607dc28d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg @@ -32,4 +32,3 @@ int16 MIN = -1023 int16 MAX = 1023 int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index d32f91b10..9484263ff 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg index cd1bbd0d9..91afc5574 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg @@ -40,14 +40,14 @@ bool limited_quantity string emergency_action_code bool emergency_action_code_is_present -uint8 EMERGENCY_ACTION_CODE_LENGTH_MIN = 1 -uint8 EMERGENCY_ACTION_CODE_LENGTH_MAX = 24 +uint8 EMERGENCY_ACTION_CODE_MIN_SIZE = 1 +uint8 EMERGENCY_ACTION_CODE_MAX_SIZE = 24 PhoneNumber phone_number bool phone_number_is_present string company_name bool company_name_is_present -uint8 COMPANY_NAME_LENGTH_MIN = 1 -uint8 COMPANY_NAME_LENGTH_MAX = 24 +uint8 COMPANY_NAME_MIN_SIZE = 1 +uint8 COMPANY_NAME_MAX_SIZE = 24 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg index fc81522ad..52ec15222 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg @@ -38,4 +38,3 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg index 9e3df25b6..19e2b4ffd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg @@ -33,4 +33,3 @@ int16 MAX = 12800 int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg index 8a72373f9..b9977f0d4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg @@ -33,4 +33,3 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg index d32f293d9..73d04ec5a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg @@ -33,4 +33,3 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg index 569cfd6d6..d67682243 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF DigitalMap ReferencePosition[] array -uint16 LENGTH_MIN = 1 -uint16 LENGTH_MAX = 256 \ No newline at end of file +uint16 MIN_SIZE = 1 +uint16 MAX_SIZE = 256 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg index 220968a79..43ea6ca1c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg @@ -29,6 +29,6 @@ uint8[] value uint8 bits_unused -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 13 +uint8 MIN_SIZE_BITS = 1 +uint8 MAX_SIZE_BITS = 13 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg index d521c7c58..d9a335ed9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg @@ -32,4 +32,3 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 5f1439a2d..33eb4fbbd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg index cd3856bf9..ffdd50c96 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg @@ -37,4 +37,3 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg index d48877dd8..6cc1045b6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF EventHistory EventPoint[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 23 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 23 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg index d191062ca..77a240fb1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg @@ -38,4 +38,3 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg index 3fd33045a..a790e6432 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg @@ -31,4 +31,3 @@ uint16 value uint16 MIN = 0 uint16 MAX = 65535 uint16 ONE_MILLI_SEC = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index c7b360731..762fd771a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index 63495337b..ff1002498 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -36,4 +36,3 @@ uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index 961c2dabb..aff6952f3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -38,4 +38,3 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 7aea67d58..5b1536bee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -40,4 +40,3 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg index 378afb7c0..18b074792 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg @@ -34,4 +34,3 @@ uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg index 22c0493e4..bf95b1054 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg @@ -35,4 +35,3 @@ uint16 WGS_84_EAST = 900 uint16 WGS_84_SOUTH = 1800 uint16 WGS_84_WEST = 2700 uint16 UNAVAILABLE = 3601 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg index d5cfb65c4..6456533de 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 100 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 6b69511e2..879b64b81 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -34,4 +34,3 @@ uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg index 35e538c4b..3a91e85c7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg index 43e2a2799..bd50329f8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg @@ -33,4 +33,3 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg index 41b54a3c8..4b62379b8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF ItineraryPath ReferencePosition[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 40 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 40 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg index b5c4b5740..16d132739 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg @@ -47,6 +47,5 @@ uint8 MESSAGE_ID_EVCSN = 11 uint8 MESSAGE_ID_SAEM = 12 uint8 MESSAGE_ID_RTCMEM = 13 - StationID station_id diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg index 655869fa9..14b6304e1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg @@ -34,4 +34,3 @@ int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg index 329b4a154..ff380dc60 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg @@ -33,4 +33,3 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg index 918857d42..c7cd97580 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg @@ -33,4 +33,3 @@ int32 MAX = 900000001 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg index d86ad6e16..b58c05ebb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg @@ -32,4 +32,3 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg index 21539c674..341e21778 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg @@ -33,4 +33,3 @@ int32 MAX = 1800000001 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg index 30653502d..e5e387119 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg @@ -33,4 +33,3 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg index 7b2e01aa6..09d9ceb5c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg @@ -32,4 +32,3 @@ uint8 MIN = 0 uint8 MAX = 127 uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg index b5e9697e9..f95b5adbc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg @@ -31,4 +31,3 @@ int64 value int64 MIN = 1 int64 MAX = 65535 int64 TEN_MILLI_SECONDS_IN_PAST = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg index 6ffb371be..9a72d15bc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF PathHistory PathPoint[] array -uint8 LENGTH_MIN = 0 -uint8 LENGTH_MAX = 40 \ No newline at end of file +uint8 MIN_SIZE = 0 +uint8 MAX_SIZE = 40 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg index 8cf5eeec5..5e2f9a67f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg @@ -33,4 +33,3 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg index 1e9128d00..18bb04a98 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 63 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg index 606b67039..8cfd73ba9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 20 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg index b01c3342b..5efdc3d90 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg index 3f3cc73e9..6294ffc82 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 30 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg index 5837d8005..72347aba9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg @@ -50,4 +50,3 @@ uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg index 015f83995..824502493 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF PositionOfPillars PosPillar[] array -int64 LENGTH_MIN = 1 -int64 LENGTH_MAX = 3 \ No newline at end of file +int64 MIN_SIZE = 1 +int64 MAX_SIZE = 3 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg index 8a1777231..5dabb7149 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg index b5e61b046..43650b6c2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF ProtectedCommunicationZonesRSU ProtectedCommunicationZone[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 16 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 16 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg index e2a5a4e8e..adf686ea1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg @@ -31,4 +31,3 @@ int64 value int64 MIN = 1 int64 MAX = 255 int64 ONE_METER = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg index 6a7a5bda6..16c038fa4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNDEFINED_CODING_TYPE = 0 uint8 R_09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index bd3a50097..aed759dcc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -36,4 +36,3 @@ uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg index 46ce145ca..ebdb78e61 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF RestrictedTypes StationType[] array -int64 LENGTH_MIN = 1 -int64 LENGTH_MAX = 3 \ No newline at end of file +int64 MIN_SIZE = 1 +int64 MAX_SIZE = 3 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg index b6575d73e..1b12c35e4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg @@ -37,4 +37,3 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg index eaa61cf9e..c4c1c38ec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg @@ -33,4 +33,3 @@ uint16 MAX = 4095 uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg index 0887a5941..bb8a3c386 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg @@ -34,4 +34,3 @@ uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg index 192a08311..faf4093de 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg @@ -39,4 +39,3 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg index 743017c33..8444a35ea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg @@ -34,4 +34,3 @@ uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg index 04391b581..930449281 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg @@ -34,4 +34,3 @@ uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg index b54a37c8a..3fd12e847 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg @@ -31,4 +31,3 @@ uint8 value uint8 MIN = 1 uint8 MAX = 255 uint8 ONE_KM_PER_HOUR = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg index 15c55d7a2..9617fb469 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg @@ -33,4 +33,3 @@ uint16 MAX = 16383 uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg index 08547aaa6..82a3cc1ea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg @@ -43,4 +43,3 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg index 3b8bdb501..108080973 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -36,4 +36,3 @@ uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg index c693654a8..7c3d46b9a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg @@ -33,4 +33,3 @@ uint8 MAX = 127 uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg index 2d6e2b766..c50be3980 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg @@ -34,4 +34,3 @@ int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg index cc883d230..09dc259a9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg @@ -33,4 +33,3 @@ int8 MAX = 67 int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 int8 ONE_DEGREE_CELSIUS = 1 int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg index d41d01815..d8a0429ed 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg @@ -32,4 +32,3 @@ uint64 MIN = 0 uint64 MAX = 4398046511103 uint64 UTC_START_OF_2004 = 0 uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg index 45e61c7a9..5f5504458 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF Traces PathHistory[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 7 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 7 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg index 310a34eb7..bf5bd835c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg @@ -39,4 +39,3 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg index 6b411b09e..a7edb7d27 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg @@ -32,4 +32,3 @@ uint16 MIN = 1 uint16 MAX = 10000 uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg index 50a96cf26..abab38688 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 255 uint8 POINT_4_METERS = 1 uint8 UNAVAILABLE = 255 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg index 494e18e75..a1c798831 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg @@ -32,4 +32,3 @@ uint32 MIN = 0 uint32 MAX = 86400 uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg index 8ad8d31f5..1b76f5b68 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -40,4 +40,3 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg index c4136bc96..727323452 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg @@ -33,4 +33,3 @@ uint16 MAX = 1023 uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg index f5895ca82..d849f7995 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg @@ -32,4 +32,3 @@ uint16 MIN = 1 uint16 MAX = 1024 uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg index c86ebc997..a3f87bd07 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg @@ -33,4 +33,3 @@ uint8 MAX = 62 uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg index 692493880..4a7a480e6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg @@ -33,4 +33,3 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg index e8a16e042..89fdb9ad3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg index df60cdcea..900dbc587 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 - diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg index 86fb2e26b..d3ebfedd5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg @@ -34,4 +34,3 @@ int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg index f01b8f344..2c96c29bd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg @@ -33,4 +33,3 @@ uint8 MAX = 102 uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg index 8a147710d..59891bb3a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg @@ -37,4 +37,3 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg index 17db3e428..2e85a1965 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg @@ -39,4 +39,3 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 08ca22f25..4d5baa2ef 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -41,4 +41,3 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index bd619386f..a45f41e0f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -37,4 +37,3 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index ec4889e8f..afe120d54 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -34,4 +34,3 @@ uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 512dbd14a..84b13bbde 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -39,4 +39,3 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg index c804dadb1..4dbc604e6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg @@ -33,4 +33,3 @@ int32 MAX = 800001 int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg index 0db806cca..61c553d96 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg @@ -57,4 +57,3 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg index 9181725da..a1439f329 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg index 3b87030fe..1607dc28d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg @@ -32,4 +32,3 @@ int16 MIN = -1023 int16 MAX = 1023 int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index d32f91b10..9484263ff 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg index cd1bbd0d9..91afc5574 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg @@ -40,14 +40,14 @@ bool limited_quantity string emergency_action_code bool emergency_action_code_is_present -uint8 EMERGENCY_ACTION_CODE_LENGTH_MIN = 1 -uint8 EMERGENCY_ACTION_CODE_LENGTH_MAX = 24 +uint8 EMERGENCY_ACTION_CODE_MIN_SIZE = 1 +uint8 EMERGENCY_ACTION_CODE_MAX_SIZE = 24 PhoneNumber phone_number bool phone_number_is_present string company_name bool company_name_is_present -uint8 COMPANY_NAME_LENGTH_MIN = 1 -uint8 COMPANY_NAME_LENGTH_MAX = 24 +uint8 COMPANY_NAME_MIN_SIZE = 1 +uint8 COMPANY_NAME_MAX_SIZE = 24 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg index fc81522ad..52ec15222 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg @@ -38,4 +38,3 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg index 9e3df25b6..19e2b4ffd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg @@ -33,4 +33,3 @@ int16 MAX = 12800 int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg index 8a72373f9..b9977f0d4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg @@ -33,4 +33,3 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg index d32f293d9..73d04ec5a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg @@ -33,4 +33,3 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg index 569cfd6d6..d67682243 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF DigitalMap ReferencePosition[] array -uint16 LENGTH_MIN = 1 -uint16 LENGTH_MAX = 256 \ No newline at end of file +uint16 MIN_SIZE = 1 +uint16 MAX_SIZE = 256 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg index 220968a79..43ea6ca1c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg @@ -29,6 +29,6 @@ uint8[] value uint8 bits_unused -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 13 +uint8 MIN_SIZE_BITS = 1 +uint8 MAX_SIZE_BITS = 13 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg index d521c7c58..d9a335ed9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg @@ -32,4 +32,3 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 5f1439a2d..33eb4fbbd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg index cd3856bf9..ffdd50c96 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg @@ -37,4 +37,3 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg index d48877dd8..6cc1045b6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF EventHistory EventPoint[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 23 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 23 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg index d191062ca..77a240fb1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg @@ -38,4 +38,3 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index c7b360731..762fd771a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index 63495337b..ff1002498 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -36,4 +36,3 @@ uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index 961c2dabb..aff6952f3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -38,4 +38,3 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 7aea67d58..5b1536bee 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -40,4 +40,3 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg index 378afb7c0..18b074792 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg @@ -34,4 +34,3 @@ uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg index 22c0493e4..bf95b1054 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg @@ -35,4 +35,3 @@ uint16 WGS_84_EAST = 900 uint16 WGS_84_SOUTH = 1800 uint16 WGS_84_WEST = 2700 uint16 UNAVAILABLE = 3601 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg index d5cfb65c4..6456533de 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 100 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 6b69511e2..879b64b81 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -34,4 +34,3 @@ uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg index 35e538c4b..3a91e85c7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg index 43e2a2799..bd50329f8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg @@ -33,4 +33,3 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg index 41b54a3c8..4b62379b8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF ItineraryPath ReferencePosition[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 40 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 40 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg index b5c4b5740..16d132739 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg @@ -47,6 +47,5 @@ uint8 MESSAGE_ID_EVCSN = 11 uint8 MESSAGE_ID_SAEM = 12 uint8 MESSAGE_ID_RTCMEM = 13 - StationID station_id diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg index 655869fa9..14b6304e1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg @@ -34,4 +34,3 @@ int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg index 329b4a154..ff380dc60 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg @@ -33,4 +33,3 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg index 918857d42..c7cd97580 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg @@ -33,4 +33,3 @@ int32 MAX = 900000001 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg index d86ad6e16..b58c05ebb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg @@ -32,4 +32,3 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg index 21539c674..341e21778 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg @@ -33,4 +33,3 @@ int32 MAX = 1800000001 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg index 30653502d..e5e387119 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg @@ -33,4 +33,3 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg index 7b2e01aa6..09d9ceb5c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg @@ -32,4 +32,3 @@ uint8 MIN = 0 uint8 MAX = 127 uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg index b5e9697e9..f95b5adbc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg @@ -31,4 +31,3 @@ int64 value int64 MIN = 1 int64 MAX = 65535 int64 TEN_MILLI_SECONDS_IN_PAST = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg index 6ffb371be..9a72d15bc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF PathHistory PathPoint[] array -uint8 LENGTH_MIN = 0 -uint8 LENGTH_MAX = 40 \ No newline at end of file +uint8 MIN_SIZE = 0 +uint8 MAX_SIZE = 40 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg index 8cf5eeec5..5e2f9a67f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg @@ -33,4 +33,3 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg index 1e9128d00..18bb04a98 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 63 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg index 606b67039..8cfd73ba9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 20 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg index b01c3342b..5efdc3d90 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg index 3f3cc73e9..6294ffc82 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 30 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg index 5837d8005..72347aba9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg @@ -50,4 +50,3 @@ uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg index 015f83995..824502493 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF PositionOfPillars PosPillar[] array -int64 LENGTH_MIN = 1 -int64 LENGTH_MAX = 3 \ No newline at end of file +int64 MIN_SIZE = 1 +int64 MAX_SIZE = 3 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg index 8a1777231..5dabb7149 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg @@ -35,4 +35,3 @@ uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg index b5e61b046..43650b6c2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF ProtectedCommunicationZonesRSU ProtectedCommunicationZone[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 16 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 16 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg index e2a5a4e8e..adf686ea1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg @@ -31,4 +31,3 @@ int64 value int64 MIN = 1 int64 MAX = 255 int64 ONE_METER = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg index 6a7a5bda6..16c038fa4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNDEFINED_CODING_TYPE = 0 uint8 R_09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg index 7c2b9b329..7764cad05 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF ReferenceDenms ActionID[] array -int64 LENGTH_MIN = 1 -int64 LENGTH_MAX = 8 \ No newline at end of file +int64 MIN_SIZE = 1 +int64 MAX_SIZE = 8 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index bd3a50097..aed759dcc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -36,4 +36,3 @@ uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg index 46ce145ca..ebdb78e61 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF RestrictedTypes StationType[] array -int64 LENGTH_MIN = 1 -int64 LENGTH_MAX = 3 \ No newline at end of file +int64 MIN_SIZE = 1 +int64 MAX_SIZE = 3 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg index b6575d73e..1b12c35e4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg @@ -37,4 +37,3 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg index eaa61cf9e..c4c1c38ec 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg @@ -33,4 +33,3 @@ uint16 MAX = 4095 uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg index 0887a5941..bb8a3c386 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg @@ -34,4 +34,3 @@ uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg index 192a08311..faf4093de 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg @@ -39,4 +39,3 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg index 743017c33..8444a35ea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg @@ -34,4 +34,3 @@ uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg index 04391b581..930449281 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg @@ -34,4 +34,3 @@ uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg index b54a37c8a..3fd12e847 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg @@ -31,4 +31,3 @@ uint8 value uint8 MIN = 1 uint8 MAX = 255 uint8 ONE_KM_PER_HOUR = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg index 15c55d7a2..9617fb469 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg @@ -33,4 +33,3 @@ uint16 MAX = 16383 uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg index 08547aaa6..82a3cc1ea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg @@ -43,4 +43,3 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg index 3b8bdb501..108080973 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -36,4 +36,3 @@ uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg index c693654a8..7c3d46b9a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg @@ -33,4 +33,3 @@ uint8 MAX = 127 uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg index 2d6e2b766..c50be3980 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg @@ -34,4 +34,3 @@ int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg index cc883d230..09dc259a9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg @@ -33,4 +33,3 @@ int8 MAX = 67 int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 int8 ONE_DEGREE_CELSIUS = 1 int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg index d41d01815..d8a0429ed 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg @@ -32,4 +32,3 @@ uint64 MIN = 0 uint64 MAX = 4398046511103 uint64 UTC_START_OF_2004 = 0 uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg index 45e61c7a9..5f5504458 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg @@ -28,5 +28,5 @@ ## SEQUENCE-OF Traces PathHistory[] array -uint8 LENGTH_MIN = 1 -uint8 LENGTH_MAX = 7 \ No newline at end of file +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 7 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg index 310a34eb7..bf5bd835c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg @@ -39,4 +39,3 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg index 6b411b09e..a7edb7d27 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg @@ -32,4 +32,3 @@ uint16 MIN = 1 uint16 MAX = 10000 uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg index 50a96cf26..abab38688 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 255 uint8 POINT_4_METERS = 1 uint8 UNAVAILABLE = 255 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg index 494e18e75..a1c798831 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg @@ -32,4 +32,3 @@ uint32 MIN = 0 uint32 MAX = 86400 uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg index 8ad8d31f5..1b76f5b68 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -40,4 +40,3 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg index c4136bc96..727323452 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg @@ -33,4 +33,3 @@ uint16 MAX = 1023 uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg index f5895ca82..d849f7995 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg @@ -32,4 +32,3 @@ uint16 MIN = 1 uint16 MAX = 1024 uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg index c86ebc997..a3f87bd07 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg @@ -33,4 +33,3 @@ uint8 MAX = 62 uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg index 692493880..4a7a480e6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg @@ -33,4 +33,3 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg index e8a16e042..89fdb9ad3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg @@ -32,4 +32,3 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg index df60cdcea..900dbc587 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -33,4 +33,3 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 - diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg index 86fb2e26b..d3ebfedd5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg @@ -34,4 +34,3 @@ int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 - diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/template.rs b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs index 1b4eda1bf..bc0c59091 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs @@ -2,7 +2,7 @@ use crate::common::{to_ros_const_case, to_ros_snake_case, to_ros_title_case, to_ use crate::conversion::utils::{InnerTypes, NameType, NamedSeqMember}; use crate::conversion::ConversionOptions; -use std::collections::HashMap; +use std::collections::{HashMap, HashSet}; const CONVERSION_TEMPLATE: &str = r#"/** ============================================================================ @@ -36,9 +36,7 @@ SOFTWARE. {comments} #pragma once - -#include - +{extra-includes} #include {c_includes} #ifdef ROS1 @@ -68,6 +66,7 @@ pub fn conversion_template( comments: &str, pdu: &str, includes: &Vec, + extra_includes: &Vec<&str>, name: &str, asn1_type: &str, to_ros_members: &str, @@ -94,6 +93,8 @@ pub fn conversion_template( ) } }) + .collect::>() + .into_iter() .collect::>() .join("\n"); let ros1_includes = format!( @@ -107,8 +108,16 @@ pub fn conversion_template( ros_fn = to_ros_snake_case(name) ); + let extra_includes = extra_includes + .iter() + .fold( + String::from(if extra_includes.len() > 0 { "\n" } else { "" }), + |acc, inc| acc + &format!("#include <{inc}>\n") + ); + CONVERSION_TEMPLATE .replace("{comments}", comments) + .replace("{extra-includes}", &extra_includes) .replace("{c_includes}", &c_includes) .replace("{ros1_includes}", &ros1_includes) .replace("{ros2_includes}", &ros2_includes) @@ -138,6 +147,7 @@ pub fn typealias_template( is_primitive: false, inner_types: None, }], + &vec![], name, "TYPEALIAS", &format!("toRos_{alias}(in, out.value);"), @@ -168,6 +178,7 @@ pub fn integer_template(options: &ConversionOptions, comments: &str, name: &str) is_primitive: true, inner_types: None, }], + &vec![], name, "INTEGER", "etsi_its_primitives_conversion::toRos_INTEGER(in, out.value);", @@ -193,6 +204,7 @@ pub fn bit_string_template(options: &ConversionOptions, comments: &str, name: &s is_primitive: true, inner_types: None, }], + &vec![], name, "BIT-STRING", "etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value);\n \ @@ -212,6 +224,7 @@ pub fn octet_string_template(options: &ConversionOptions, comments: &str, name: is_primitive: true, inner_types: None, }], + &vec![], name, "OCTET-STRING", "etsi_its_primitives_conversion::toRos_OCTET_STRING(in, out.value);", @@ -234,6 +247,7 @@ pub fn char_string_template( is_primitive: true, inner_types: None, }], + &vec![], name, string_type, &format!("etsi_its_primitives_conversion::toRos_{string_type}(in, out.value);"), @@ -251,6 +265,7 @@ pub fn boolean_template(options: &ConversionOptions, comments: &str, name: &str) is_primitive: true, inner_types: None, }], + &vec![], name, "BOOLEAN", "etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value);", @@ -293,6 +308,7 @@ pub fn enumerated_template(options: &ConversionOptions, comments: &str, name: &s comments, &options.main_pdu, &vec![], + &vec![], name, "ENUMERATED", "out.value = in;", @@ -525,6 +541,7 @@ pub fn sequence_or_set_template( comments, &options.main_pdu, &includes, + &vec![], name, "SEQUENCE", &to_ros_members, @@ -575,6 +592,7 @@ pub fn sequence_or_set_of_template( inner_types: None, }, ], + &vec!["stdexcept"], name, "SEQUENCE-OF", &to_ros_loop, @@ -666,6 +684,7 @@ pub fn choice_template( comments, &options.main_pdu, &members, + &vec![], name, "CHOICE", &to_ros_members, diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs index 836433284..50f644bee 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs @@ -174,7 +174,7 @@ pub fn generate_bit_string(tld: ToplevelTypeDefinition) -> Result(), per_constraints.is_extensible(), ); - let range_prefix = if per_constraints.is_size_constraint() { - "LENGTH_" + let range_suffix = if per_constraints.is_size_constraint() { + "_SIZE" } else { "" }; @@ -101,36 +101,36 @@ pub fn format_constraints( ) { (Some(min), Some(max), true) if min == max => { format!( - "{range_type} {{prefix}}{range_prefix}MIN = {min}\n\ - {range_type} {{prefix}}{range_prefix}MAX = {max}" + "{range_type} {{prefix}}MIN{range_suffix} = {min}\n\ + {range_type} {{prefix}}MAX{range_suffix} = {max}" ) } (Some(min), Some(max), true) => { format!( - "{range_type} {{prefix}}{range_prefix}MIN = {min}\n\ - {range_type} {{prefix}}{range_prefix}MAX = {max}" + "{range_type} {{prefix}}MIN{range_suffix} = {min}\n\ + {range_type} {{prefix}}MAX{range_suffix} = {max}" ) } (Some(min), Some(max), false) if min == max => { - format!("{range_type} {{prefix}}{range_prefix} = {min}", range_prefix = range_prefix.replace("_","")) + format!("{range_type} {{prefix}}{range_suffix} = {min}", range_suffix = range_suffix.replace("_","")) } (Some(min), Some(max), false) => { format!( - "{range_type} {{prefix}}{range_prefix}MIN = {min}\n\ - {range_type} {{prefix}}{range_prefix}MAX = {max}" + "{range_type} {{prefix}}MIN{range_suffix} = {min}\n\ + {range_type} {{prefix}}MAX{range_suffix} = {max}" ) } (Some(min), None, true) => { - format!("{range_type} {{prefix}}{range_prefix}MIN = {min}") + format!("{range_type} {{prefix}}MIN{range_suffix} = {min}") } (Some(min), None, false) => { - format!("{range_type} {{prefix}}{range_prefix}MIN = {min}") + format!("{range_type} {{prefix}}MIN{range_suffix} = {min}") } (None, Some(max), true) => { - format!("{range_type} {{prefix}}{range_prefix}MAX = {max}") + format!("{range_type} {{prefix}}MAX{range_suffix} = {max}") } (None, Some(max), false) => { - format!("{range_type} {{prefix}}{range_prefix}MAX = {max}") + format!("{range_type} {{prefix}}MAX{range_suffix} = {max}") } _ => "".into(), }, @@ -147,13 +147,17 @@ pub fn get_distinguished_values(ty: &ASN1Type) -> Option pub fn format_distinguished_values(dvalues: &Option>) -> String { let mut result = String::from(""); if let Some(dvalues) = dvalues { - dvalues.iter().for_each(|dvalue| { - result.push_str(&format!( - "{{type}} {{prefix}}{} = {}\n", - to_ros_const_case(&dvalue.name), - dvalue.value - )); - }); + result = dvalues + .iter() + .map(|dvalue| { + format!( + "{{type}} {{prefix}}{} = {}", + to_ros_const_case(&dvalue.name), + dvalue.value + ) + }) + .collect::>() + .join("\n"); } result } From bd3169b34b736272a6cdfe355e61a6a145c79f7d Mon Sep 17 00:00:00 2001 From: v0-e Date: Thu, 6 Jun 2024 22:21:44 +0100 Subject: [PATCH 15/22] rgen: Include original ASN.1 defs in ROS .msgs (using Python parser) --- .../etsi_its_cam_conversion/convertActionID.h | 2 +- .../etsi_its_cam_conversion/convertAltitude.h | 2 +- ...onvertBasicVehicleContainerHighFrequency.h | 20 +++---- .../etsi_its_cam_conversion/convertCAM.h | 2 +- .../convertCamParameters.h | 2 +- .../convertCenDsrcTollingZone.h | 2 +- .../convertDangerousGoodsExtended.h | 6 +-- .../convertDeltaReferencePosition.h | 2 +- .../convertEmergencyContainer.h | 2 +- .../convertEventHistory.h | 2 +- .../convertEventPoint.h | 2 +- .../etsi_its_cam_conversion/convertHeading.h | 2 +- .../convertItsPduHeader.h | 2 +- .../convertLateralAcceleration.h | 2 +- .../convertPathPoint.h | 2 +- .../convertPosConfidenceEllipse.h | 2 +- .../convertProtectedCommunicationZone.h | 6 +-- .../convertPtActivation.h | 2 +- .../convertPublicTransportContainer.h | 2 +- .../convertReferencePosition.h | 4 +- .../convertRestrictedTypes.h | 2 +- .../convertRoadWorksContainerBasic.h | 2 +- .../convertSafetyCarContainer.h | 4 +- .../convertSpecialTransportContainer.h | 2 +- .../convertSpecialVehicleContainer.h | 6 +-- .../etsi_its_cam_conversion/convertSpeed.h | 2 +- .../etsi_its_cam_conversion/convertTraces.h | 2 +- .../convertVehicleIdentification.h | 2 +- .../convertVehicleLength.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../etsi_its_cam_conversion/convertYawRate.h | 2 +- .../convertActionID.h | 2 +- .../convertAlacarteContainer.h | 2 +- .../convertAltitude.h | 2 +- .../convertCauseCode.h | 2 +- .../convertClosedLanes.h | 2 +- .../convertCurvature.h | 2 +- .../convertDangerousGoodsExtended.h | 10 ++-- ...tralizedEnvironmentalNotificationMessage.h | 2 +- .../convertDeltaReferencePosition.h | 4 +- .../convertEventPoint.h | 2 +- .../etsi_its_denm_conversion/convertHeading.h | 2 +- .../convertImpactReductionContainer.h | 10 ++-- .../convertItineraryPath.h | 2 +- .../convertLocationContainer.h | 2 +- .../convertLongitudinalAcceleration.h | 2 +- .../convertManagementContainer.h | 10 ++-- .../convertPathPoint.h | 2 +- .../convertPosConfidenceEllipse.h | 2 +- .../convertPositionOfPillars.h | 2 +- .../convertProtectedCommunicationZone.h | 8 +-- .../convertReferenceDenms.h | 2 +- .../convertReferencePosition.h | 2 +- .../convertRoadWorksContainerExtended.h | 10 ++-- .../convertStationaryVehicleContainer.h | 6 +-- .../convertSteeringWheelAngle.h | 2 +- .../etsi_its_denm_conversion/convertTraces.h | 2 +- .../convertVehicleIdentification.h | 2 +- .../convertVehicleLength.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../etsi_its_denm_conversion/convertYawRate.h | 2 +- .../msg/AccelerationConfidence.msg | 4 +- .../msg/AccelerationControl.msg | 12 ++++- .../msg/AccidentSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/ActionID.msg | 7 ++- ...seWeatherConditionAdhesionSubCauseCode.msg | 4 +- ...ionExtremeWeatherConditionSubCauseCode.msg | 4 +- ...therConditionPrecipitationSubCauseCode.msg | 4 +- ...WeatherConditionVisibilitySubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/Altitude.msg | 7 ++- .../msg/AltitudeConfidence.msg | 21 +++++++- .../etsi_its_cam_msgs/msg/AltitudeValue.msg | 4 +- .../etsi_its_cam_msgs/msg/BasicContainer.msg | 8 ++- .../BasicVehicleContainerHighFrequency.msg | 21 +++++++- .../msg/BasicVehicleContainerLowFrequency.msg | 8 ++- etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg | 7 ++- .../etsi_its_cam_msgs/msg/CamParameters.msg | 10 +++- .../etsi_its_cam_msgs/msg/CauseCode.msg | 8 ++- .../etsi_its_cam_msgs/msg/CauseCodeType.msg | 32 ++++++++++- .../msg/CenDsrcTollingZone.msg | 9 +++- .../msg/CenDsrcTollingZoneID.msg | 4 +- .../etsi_its_cam_msgs/msg/ClosedLanes.msg | 9 +++- .../msg/CollisionRiskSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/CoopAwareness.msg | 7 ++- .../etsi_its_cam_msgs/msg/Curvature.msg | 7 ++- .../msg/CurvatureCalculationMode.msg | 4 +- .../msg/CurvatureConfidence.msg | 13 ++++- .../etsi_its_cam_msgs/msg/CurvatureValue.msg | 4 +- .../msg/DangerousEndOfQueueSubCauseCode.msg | 4 +- .../msg/DangerousGoodsBasic.msg | 25 ++++++++- .../msg/DangerousGoodsContainer.msg | 6 ++- .../msg/DangerousGoodsExtended.msg | 14 ++++- .../msg/DangerousSituationSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/DeltaAltitude.msg | 4 +- .../etsi_its_cam_msgs/msg/DeltaLatitude.msg | 4 +- .../etsi_its_cam_msgs/msg/DeltaLongitude.msg | 4 +- .../msg/DeltaReferencePosition.msg | 8 ++- .../etsi_its_cam_msgs/msg/DigitalMap.msg | 4 +- .../etsi_its_cam_msgs/msg/DriveDirection.msg | 4 +- .../msg/DrivingLaneStatus.msg | 4 +- .../msg/EmbarkationStatus.msg | 4 +- .../msg/EmergencyContainer.msg | 8 ++- .../msg/EmergencyPriority.msg | 4 +- ...mergencyVehicleApproachingSubCauseCode.msg | 4 +- .../msg/EnergyStorageType.msg | 4 +- .../etsi_its_cam_msgs/msg/EventHistory.msg | 4 +- .../etsi_its_cam_msgs/msg/EventPoint.msg | 8 ++- .../etsi_its_cam_msgs/msg/ExteriorLights.msg | 13 ++++- .../msg/GenerationDeltaTime.msg | 4 +- .../msg/HardShoulderStatus.msg | 4 +- ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 4 +- ...dousLocationDangerousCurveSubCauseCode.msg | 4 +- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 4 +- ...usLocationSurfaceConditionSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/Heading.msg | 7 ++- .../msg/HeadingConfidence.msg | 4 +- .../etsi_its_cam_msgs/msg/HeadingValue.msg | 4 +- .../etsi_its_cam_msgs/msg/HeightLonCarr.msg | 4 +- .../msg/HighFrequencyContainer.msg | 8 ++- .../HumanPresenceOnTheRoadSubCauseCode.msg | 4 +- .../msg/HumanProblemSubCauseCode.msg | 4 +- .../msg/InformationQuality.msg | 4 +- .../etsi_its_cam_msgs/msg/ItineraryPath.msg | 4 +- .../etsi_its_cam_msgs/msg/ItsPduHeader.msg | 6 ++- .../etsi_its_cam_msgs/msg/LanePosition.msg | 5 +- .../msg/LateralAcceleration.msg | 7 ++- .../msg/LateralAccelerationValue.msg | 4 +- .../etsi_its_cam_msgs/msg/Latitude.msg | 4 +- .../msg/LightBarSirenInUse.msg | 7 ++- .../etsi_its_cam_msgs/msg/Longitude.msg | 4 +- .../msg/LongitudinalAcceleration.msg | 7 ++- .../msg/LongitudinalAccelerationValue.msg | 4 +- .../msg/LowFrequencyContainer.msg | 7 ++- .../msg/NumberOfOccupants.msg | 4 +- .../msg/OpeningDaysHours.msg | 4 +- .../etsi_its_cam_msgs/msg/PathDeltaTime.msg | 4 +- .../etsi_its_cam_msgs/msg/PathHistory.msg | 4 +- .../etsi_its_cam_msgs/msg/PathPoint.msg | 7 ++- .../msg/PerformanceClass.msg | 4 +- .../etsi_its_cam_msgs/msg/PhoneNumber.msg | 4 +- .../etsi_its_cam_msgs/msg/PosCentMass.msg | 4 +- .../msg/PosConfidenceEllipse.msg | 8 ++- .../etsi_its_cam_msgs/msg/PosFrontAx.msg | 4 +- .../etsi_its_cam_msgs/msg/PosLonCarr.msg | 4 +- .../etsi_its_cam_msgs/msg/PosPillar.msg | 4 +- .../msg/PositionOfOccupants.msg | 24 ++++++++- .../msg/PositionOfPillars.msg | 4 +- .../msg/PositioningSolutionType.msg | 4 +- .../msg/PostCrashSubCauseCode.msg | 4 +- .../msg/ProtectedCommunicationZone.msg | 12 ++++- .../msg/ProtectedCommunicationZonesRSU.msg | 4 +- .../etsi_its_cam_msgs/msg/ProtectedZoneID.msg | 4 +- .../msg/ProtectedZoneRadius.msg | 4 +- .../msg/ProtectedZoneType.msg | 4 +- .../etsi_its_cam_msgs/msg/PtActivation.msg | 7 ++- .../msg/PtActivationData.msg | 4 +- .../msg/PtActivationType.msg | 4 +- .../msg/PublicTransportContainer.msg | 7 ++- .../msg/RSUContainerHighFrequency.msg | 7 ++- .../msg/ReferencePosition.msg | 9 +++- .../msg/RelevanceDistance.msg | 4 +- .../msg/RelevanceTrafficDirection.msg | 4 +- .../msg/RequestResponseIndication.msg | 4 +- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/RescueContainer.msg | 6 ++- .../etsi_its_cam_msgs/msg/RestrictedTypes.msg | 4 +- .../etsi_its_cam_msgs/msg/RoadType.msg | 8 ++- .../msg/RoadWorksContainerBasic.msg | 8 ++- .../msg/RoadworksSubCauseCode.msg | 4 +- .../msg/SafetyCarContainer.msg | 9 +++- .../etsi_its_cam_msgs/msg/SemiAxisLength.msg | 4 +- .../etsi_its_cam_msgs/msg/SequenceNumber.msg | 4 +- .../msg/SignalViolationSubCauseCode.msg | 4 +- .../msg/SlowVehicleSubCauseCode.msg | 4 +- .../msg/SpecialTransportContainer.msg | 7 ++- .../msg/SpecialTransportType.msg | 4 +- .../msg/SpecialVehicleContainer.msg | 13 ++++- etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg | 7 ++- .../etsi_its_cam_msgs/msg/SpeedConfidence.msg | 4 +- .../etsi_its_cam_msgs/msg/SpeedLimit.msg | 4 +- .../etsi_its_cam_msgs/msg/SpeedValue.msg | 4 +- .../etsi_its_cam_msgs/msg/StationID.msg | 4 +- .../etsi_its_cam_msgs/msg/StationType.msg | 5 +- .../etsi_its_cam_msgs/msg/StationarySince.msg | 4 +- .../msg/StationaryVehicleSubCauseCode.msg | 4 +- .../msg/SteeringWheelAngle.msg | 7 ++- .../msg/SteeringWheelAngleConfidence.msg | 4 +- .../msg/SteeringWheelAngleValue.msg | 4 +- .../msg/SubCauseCodeType.msg | 4 +- .../etsi_its_cam_msgs/msg/Temperature.msg | 4 +- .../etsi_its_cam_msgs/msg/TimestampIts.msg | 4 +- .../etsi_its_cam_msgs/msg/Traces.msg | 4 +- .../msg/TrafficConditionSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/TrafficRule.msg | 5 +- .../msg/TransmissionInterval.msg | 4 +- .../etsi_its_cam_msgs/msg/TurningRadius.msg | 4 +- etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg | 4 +- .../msg/ValidityDuration.msg | 4 +- .../msg/VehicleBreakdownSubCauseCode.msg | 4 +- .../msg/VehicleIdentification.msg | 8 ++- .../etsi_its_cam_msgs/msg/VehicleLength.msg | 7 ++- .../msg/VehicleLengthConfidenceIndication.msg | 4 +- .../msg/VehicleLengthValue.msg | 4 +- .../etsi_its_cam_msgs/msg/VehicleMass.msg | 4 +- .../etsi_its_cam_msgs/msg/VehicleRole.msg | 4 +- .../etsi_its_cam_msgs/msg/VehicleWidth.msg | 4 +- .../msg/VerticalAcceleration.msg | 7 ++- .../msg/VerticalAccelerationValue.msg | 4 +- .../etsi_its_cam_msgs/msg/WMInumber.msg | 4 +- .../msg/WheelBaseVehicle.msg | 4 +- .../msg/WrongWayDrivingSubCauseCode.msg | 4 +- .../etsi_its_cam_msgs/msg/YawRate.msg | 7 ++- .../msg/YawRateConfidence.msg | 14 ++++- .../etsi_its_cam_msgs/msg/YawRateValue.msg | 4 +- .../msg/AccelerationConfidence.msg | 4 +- .../msg/AccelerationControl.msg | 12 ++++- .../msg/AccidentSubCauseCode.msg | 4 +- .../etsi_its_denm_msgs/msg/ActionID.msg | 7 ++- ...seWeatherConditionAdhesionSubCauseCode.msg | 4 +- ...ionExtremeWeatherConditionSubCauseCode.msg | 4 +- ...therConditionPrecipitationSubCauseCode.msg | 4 +- ...WeatherConditionVisibilitySubCauseCode.msg | 4 +- .../msg/AlacarteContainer.msg | 12 ++++- .../etsi_its_denm_msgs/msg/Altitude.msg | 7 ++- .../msg/AltitudeConfidence.msg | 21 +++++++- .../etsi_its_denm_msgs/msg/AltitudeValue.msg | 4 +- .../etsi_its_denm_msgs/msg/CauseCode.msg | 8 ++- .../etsi_its_denm_msgs/msg/CauseCodeType.msg | 32 ++++++++++- .../msg/CenDsrcTollingZone.msg | 9 +++- .../msg/CenDsrcTollingZoneID.msg | 4 +- .../etsi_its_denm_msgs/msg/ClosedLanes.msg | 9 +++- .../msg/CollisionRiskSubCauseCode.msg | 4 +- .../etsi_its_denm_msgs/msg/Curvature.msg | 7 ++- .../msg/CurvatureCalculationMode.msg | 4 +- .../msg/CurvatureConfidence.msg | 13 ++++- .../etsi_its_denm_msgs/msg/CurvatureValue.msg | 4 +- etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg | 7 ++- .../msg/DangerousEndOfQueueSubCauseCode.msg | 4 +- .../msg/DangerousGoodsBasic.msg | 25 ++++++++- .../msg/DangerousGoodsExtended.msg | 14 ++++- .../msg/DangerousSituationSubCauseCode.msg | 4 +- ...alizedEnvironmentalNotificationMessage.msg | 9 +++- .../etsi_its_denm_msgs/msg/DeltaAltitude.msg | 4 +- .../etsi_its_denm_msgs/msg/DeltaLatitude.msg | 4 +- .../etsi_its_denm_msgs/msg/DeltaLongitude.msg | 4 +- .../msg/DeltaReferencePosition.msg | 8 ++- .../etsi_its_denm_msgs/msg/DigitalMap.msg | 4 +- .../etsi_its_denm_msgs/msg/DriveDirection.msg | 4 +- .../msg/DrivingLaneStatus.msg | 4 +- .../msg/EmbarkationStatus.msg | 4 +- .../msg/EmergencyPriority.msg | 4 +- ...mergencyVehicleApproachingSubCauseCode.msg | 4 +- .../msg/EnergyStorageType.msg | 4 +- .../etsi_its_denm_msgs/msg/EventHistory.msg | 4 +- .../etsi_its_denm_msgs/msg/EventPoint.msg | 8 ++- .../etsi_its_denm_msgs/msg/ExteriorLights.msg | 13 ++++- .../msg/HardShoulderStatus.msg | 4 +- ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 4 +- ...dousLocationDangerousCurveSubCauseCode.msg | 4 +- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 4 +- ...usLocationSurfaceConditionSubCauseCode.msg | 4 +- .../etsi_its_denm_msgs/msg/Heading.msg | 7 ++- .../msg/HeadingConfidence.msg | 4 +- .../etsi_its_denm_msgs/msg/HeadingValue.msg | 4 +- .../etsi_its_denm_msgs/msg/HeightLonCarr.msg | 4 +- .../HumanPresenceOnTheRoadSubCauseCode.msg | 4 +- .../msg/HumanProblemSubCauseCode.msg | 4 +- .../msg/ImpactReductionContainer.msg | 17 +++++- .../msg/InformationQuality.msg | 4 +- .../etsi_its_denm_msgs/msg/ItineraryPath.msg | 4 +- .../etsi_its_denm_msgs/msg/ItsPduHeader.msg | 6 ++- .../etsi_its_denm_msgs/msg/LanePosition.msg | 5 +- .../msg/LateralAcceleration.msg | 7 ++- .../msg/LateralAccelerationValue.msg | 4 +- .../etsi_its_denm_msgs/msg/Latitude.msg | 4 +- .../msg/LightBarSirenInUse.msg | 7 ++- .../msg/LocationContainer.msg | 10 +++- .../etsi_its_denm_msgs/msg/Longitude.msg | 4 +- .../msg/LongitudinalAcceleration.msg | 7 ++- .../msg/LongitudinalAccelerationValue.msg | 4 +- .../msg/ManagementContainer.msg | 16 +++++- .../msg/NumberOfOccupants.msg | 4 +- .../msg/OpeningDaysHours.msg | 4 +- .../etsi_its_denm_msgs/msg/PathDeltaTime.msg | 4 +- .../etsi_its_denm_msgs/msg/PathHistory.msg | 4 +- .../etsi_its_denm_msgs/msg/PathPoint.msg | 7 ++- .../msg/PerformanceClass.msg | 4 +- .../etsi_its_denm_msgs/msg/PhoneNumber.msg | 4 +- .../etsi_its_denm_msgs/msg/PosCentMass.msg | 4 +- .../msg/PosConfidenceEllipse.msg | 8 ++- .../etsi_its_denm_msgs/msg/PosFrontAx.msg | 4 +- .../etsi_its_denm_msgs/msg/PosLonCarr.msg | 4 +- .../etsi_its_denm_msgs/msg/PosPillar.msg | 4 +- .../msg/PositionOfOccupants.msg | 24 ++++++++- .../msg/PositionOfPillars.msg | 4 +- .../msg/PositioningSolutionType.msg | 4 +- .../msg/PostCrashSubCauseCode.msg | 4 +- .../msg/ProtectedCommunicationZone.msg | 12 ++++- .../msg/ProtectedCommunicationZonesRSU.msg | 4 +- .../msg/ProtectedZoneID.msg | 4 +- .../msg/ProtectedZoneRadius.msg | 4 +- .../msg/ProtectedZoneType.msg | 4 +- .../etsi_its_denm_msgs/msg/PtActivation.msg | 7 ++- .../msg/PtActivationData.msg | 4 +- .../msg/PtActivationType.msg | 4 +- .../etsi_its_denm_msgs/msg/ReferenceDenms.msg | 4 +- .../msg/ReferencePosition.msg | 9 +++- .../msg/RelevanceDistance.msg | 4 +- .../msg/RelevanceTrafficDirection.msg | 4 +- .../msg/RequestResponseIndication.msg | 4 +- ...eAndRecoveryWorkInProgressSubCauseCode.msg | 4 +- .../msg/RestrictedTypes.msg | 4 +- .../etsi_its_denm_msgs/msg/RoadType.msg | 8 ++- .../msg/RoadWorksContainerExtended.msg | 14 ++++- .../msg/RoadworksSubCauseCode.msg | 4 +- .../etsi_its_denm_msgs/msg/SemiAxisLength.msg | 4 +- .../etsi_its_denm_msgs/msg/SequenceNumber.msg | 4 +- .../msg/SignalViolationSubCauseCode.msg | 4 +- .../msg/SituationContainer.msg | 10 +++- .../msg/SlowVehicleSubCauseCode.msg | 4 +- .../msg/SpecialTransportType.msg | 4 +- .../etsi_its_denm_msgs/msg/Speed.msg | 7 ++- .../msg/SpeedConfidence.msg | 4 +- .../etsi_its_denm_msgs/msg/SpeedLimit.msg | 4 +- .../etsi_its_denm_msgs/msg/SpeedValue.msg | 4 +- .../etsi_its_denm_msgs/msg/StationID.msg | 4 +- .../etsi_its_denm_msgs/msg/StationType.msg | 5 +- .../msg/StationarySince.msg | 4 +- .../msg/StationaryVehicleContainer.msg | 11 +++- .../msg/StationaryVehicleSubCauseCode.msg | 4 +- .../msg/SteeringWheelAngle.msg | 7 ++- .../msg/SteeringWheelAngleConfidence.msg | 4 +- .../msg/SteeringWheelAngleValue.msg | 4 +- .../msg/SubCauseCodeType.msg | 4 +- .../etsi_its_denm_msgs/msg/Temperature.msg | 4 +- .../etsi_its_denm_msgs/msg/Termination.msg | 4 +- .../etsi_its_denm_msgs/msg/TimestampIts.msg | 4 +- .../etsi_its_denm_msgs/msg/Traces.msg | 4 +- .../msg/TrafficConditionSubCauseCode.msg | 4 +- .../etsi_its_denm_msgs/msg/TrafficRule.msg | 5 +- .../msg/TransmissionInterval.msg | 4 +- .../etsi_its_denm_msgs/msg/TurningRadius.msg | 4 +- etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg | 4 +- .../msg/ValidityDuration.msg | 4 +- .../msg/VehicleBreakdownSubCauseCode.msg | 4 +- .../msg/VehicleIdentification.msg | 8 ++- .../etsi_its_denm_msgs/msg/VehicleLength.msg | 7 ++- .../msg/VehicleLengthConfidenceIndication.msg | 4 +- .../msg/VehicleLengthValue.msg | 4 +- .../etsi_its_denm_msgs/msg/VehicleMass.msg | 4 +- .../etsi_its_denm_msgs/msg/VehicleRole.msg | 4 +- .../etsi_its_denm_msgs/msg/VehicleWidth.msg | 4 +- .../msg/VerticalAcceleration.msg | 7 ++- .../msg/VerticalAccelerationValue.msg | 4 +- .../etsi_its_denm_msgs/msg/WMInumber.msg | 4 +- .../msg/WheelBaseVehicle.msg | 4 +- .../msg/WrongWayDrivingSubCauseCode.msg | 4 +- .../etsi_its_denm_msgs/msg/YawRate.msg | 7 ++- .../msg/YawRateConfidence.msg | 14 ++++- .../etsi_its_denm_msgs/msg/YawRateValue.msg | 4 +- utils/codegen/codegen-rust/asn1ToRosMsg.py | 54 +++++++++++++++++++ .../codegen-rust/rgen/src/msgs/template.rs | 12 ++--- 362 files changed, 1658 insertions(+), 405 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index 50b350be1..e175914bd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index b6ef74fe8..b484e3bdc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index 0118add42..afe8e42bf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -31,22 +31,22 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include -#include #include #include -#include -#include +#include #include +#include +#include +#include #include +#include #include -#include -#include -#include +#include #include +#include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index 45ad11a31..3d16361a5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -32,8 +32,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index 6982fd8cd..ba794fd23 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -31,10 +31,10 @@ SOFTWARE. #pragma once #include -#include #include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index 7f779c747..15865e58d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index f1733605b..78a25f890 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -31,14 +31,14 @@ SOFTWARE. #pragma once #include -#include -#include #include #include +#include #include +#include +#include #include #include -#include #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index 2e2590d87..3f5c5dbc3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index 687e41aeb..6d2b71ead 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index faab4577c..76971e076 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index 43fd203f1..52d44e0d7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index b99a2db20..ecb6555c8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h index 1987e268a..73b19f160 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index 53f8fb9a3..d0a505539 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index 742cf85c0..60041f3ca 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index 26dd633dc..be1b2d394 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index 8233ff8a2..775b3b379 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -31,11 +31,11 @@ SOFTWARE. #pragma once #include -#include +#include +#include #include +#include #include -#include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index 92ba34eb8..ba43504cd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index 79be970e7..d0f26b1e0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index e8ccd6335..6e49d9e67 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -31,10 +31,10 @@ SOFTWARE. #pragma once #include -#include -#include #include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index 28695a91b..c339b6461 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index 769751073..99bcb0c7a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index 89e1e1c9d..de3c9547a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -31,10 +31,10 @@ SOFTWARE. #pragma once #include +#include +#include #include #include -#include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h index 86254dc81..a299cf493 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index b975a8cb8..e0c0c338c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -31,12 +31,12 @@ SOFTWARE. #pragma once #include -#include #include -#include #include -#include +#include +#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index 31df3720c..cae8c8c4b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index f5c40515c..c95eb4a23 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index 2a7863712..c2de949aa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index 0e941105e..22a4e7b1c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index 12ebeb807..5d216d34b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index c8a04980a..ba06a9005 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index 45591a1aa..efeb0c841 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 60c16d0e7..4dc6076f6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #include #include #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index 9906518a7..ed0d53e4b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index 6e96d65b2..29ee5a3e0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index 3dae358b2..1cc280bce 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index 14d97441a..5b764c7a4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index acdc50b5a..1c54b57d8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -31,16 +31,16 @@ SOFTWARE. #pragma once #include -#include -#include -#include +#include +#include #include #include +#include +#include #include #include -#include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index c6d8ad131..b971b5e32 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -32,8 +32,8 @@ SOFTWARE. #include #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index aca38b575..36f00c6b9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index 28a476e1c..f2877b4ae 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index 7d471774e..e1f51d488 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index 211d25efe..0c4d34971 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -31,16 +31,16 @@ SOFTWARE. #pragma once #include +#include #include +#include #include -#include -#include -#include #include -#include +#include +#include #include +#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index efa1f46ee..952e35f8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index 3c026f8ec..fa1a0a7ff 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -32,9 +32,9 @@ SOFTWARE. #include #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index a86ad5492..8396df28e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index c930fb4cb..1a4c6c44e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -31,14 +31,14 @@ SOFTWARE. #pragma once #include -#include +#include +#include +#include #include -#include +#include #include -#include +#include #include -#include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index 0b0d41e8c..d2f972fe8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 531e91143..66b770a62 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h index e6bd20dcf..887a75980 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index 4faad85e7..2bae62082 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -31,12 +31,12 @@ SOFTWARE. #pragma once #include -#include -#include -#include #include -#include #include +#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index b53e438ea..99329a621 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index 90659a91e..5bba96e43 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -32,8 +32,8 @@ SOFTWARE. #include #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index 2a92db99b..7ad596df9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -31,15 +31,15 @@ SOFTWARE. #pragma once #include -#include -#include #include -#include +#include +#include #include +#include +#include #include +#include #include -#include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index eec23d213..1164c2a20 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -31,12 +31,12 @@ SOFTWARE. #pragma once #include +#include #include -#include +#include #include +#include #include -#include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index 9d5276877..751f23cfb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 4ce923012..7eadf0db7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index 7d768e433..f565b0169 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index 8e46738fb..68450ca58 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index 9c6593ad6..0426adc0b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h index fede6836a..b5090eb6e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg index 2c96c29bd..d8f12b08b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AccelerationConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# AccelerationConfidence ::= INTEGER {pointOneMeterPerSecSquared(1), outOfRange(101), unavailable(102)} (0 .. 102) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg index 59891bb3a..b9a2fcc83 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg @@ -25,7 +25,17 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING AccelerationControl +# --- ASN.1 Definition --------------------------------------------------------- +# AccelerationControl ::= BIT STRING { +# brakePedalEngaged (0), +# gasPedalEngaged (1), +# emergencyBrakeEngaged (2), +# collisionWarningEngaged (3), +# accEngaged (4), +# cruiseControlEngaged (5), +# speedLimiterEngaged (6) +# } (SIZE(7)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg index 2e85a1965..62efd6e30 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AccidentSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AccidentSubCauseCode ::= INTEGER {unavailable(0), multiVehicleAccident(1), heavyAccident(2), accidentInvolvingLorry(3), accidentInvolvingBus(4), accidentInvolvingHazardousMaterials(5), accidentOnOppositeLane(6), unsecuredAccident(7), assistanceRequested(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg index 14f623b35..8ebd1d181 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ActionID +# --- ASN.1 Definition --------------------------------------------------------- +# ActionID ::= SEQUENCE { +# originatingStationID StationID, +# sequenceNumber SequenceNumber +# } +# ------------------------------------------------------------------------------ StationID originating_station_id SequenceNumber sequence_number diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 4d5baa2ef..5e2955099 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionAdhesionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-AdhesionSubCauseCode ::= INTEGER {unavailable(0), heavyFrostOnRoad(1), fuelOnRoad(2), mudOnRoad(3), snowOnRoad(4), iceOnRoad(5), blackIceOnRoad(6), oilOnRoad(7), looseChippings(8), instantBlackIce(9), roadsSalted(10)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index a45f41e0f..40958b76c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-ExtremeWeatherConditionSubCauseCode ::= INTEGER {unavailable(0), strongWinds(1), damagingHail(2), hurricane(3), thunderstorm(4), tornado(5), blizzard(6)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index afe120d54..b087e8491 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-PrecipitationSubCauseCode ::= INTEGER {unavailable(0), heavyRain(1), heavySnowfall(2), softHail(3)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 84b13bbde..279aa3ad6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionVisibilitySubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-VisibilitySubCauseCode ::= INTEGER {unavailable(0), fog(1), smoke(2), heavySnowfall(3), heavyRain(4), heavyHail(5), lowSunGlare(6), sandstorms(7), swarmsOfInsects(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg index 18a7e620d..d33ad18f6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Altitude +# --- ASN.1 Definition --------------------------------------------------------- +# Altitude ::= SEQUENCE { +# altitudeValue AltitudeValue, +# altitudeConfidence AltitudeConfidence +# } +# ------------------------------------------------------------------------------ AltitudeValue altitude_value AltitudeConfidence altitude_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg index 7c3a95c22..0d49d5dfd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg @@ -25,7 +25,26 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED AltitudeConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# AltitudeConfidence ::= ENUMERATED { +# alt-000-01 (0), +# alt-000-02 (1), +# alt-000-05 (2), +# alt-000-10 (3), +# alt-000-20 (4), +# alt-000-50 (5), +# alt-001-00 (6), +# alt-002-00 (7), +# alt-005-00 (8), +# alt-010-00 (9), +# alt-020-00 (10), +# alt-050-00 (11), +# alt-100-00 (12), +# alt-200-00 (13), +# outOfRange (14), +# unavailable (15) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 ALT_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg index 4dbc604e6..ced7117ff 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AltitudeValue +# --- ASN.1 Definition --------------------------------------------------------- +# AltitudeValue ::= INTEGER {referenceEllipsoidSurface(0), oneCentimeter(1), unavailable(800001)} (-100000..800001) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -100000 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg index 77e4ac3ea..81d75ef19 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE BasicContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# BasicContainer ::= SEQUENCE { +# stationType StationType, +# referencePosition ReferencePosition, +# ... +# } +# ------------------------------------------------------------------------------ StationType station_type ReferencePosition reference_position diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg index 56da03917..93959b835 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg @@ -25,7 +25,26 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE BasicVehicleContainerHighFrequency +# --- ASN.1 Definition --------------------------------------------------------- +# BasicVehicleContainerHighFrequency ::= SEQUENCE { +# heading Heading, +# speed Speed, +# driveDirection DriveDirection, +# vehicleLength VehicleLength, +# vehicleWidth VehicleWidth, +# longitudinalAcceleration LongitudinalAcceleration, +# curvature Curvature, +# curvatureCalculationMode CurvatureCalculationMode, +# yawRate YawRate, +# accelerationControl AccelerationControl OPTIONAL, +# lanePosition LanePosition OPTIONAL, +# steeringWheelAngle SteeringWheelAngle OPTIONAL, +# lateralAcceleration LateralAcceleration OPTIONAL, +# verticalAcceleration VerticalAcceleration OPTIONAL, +# performanceClass PerformanceClass OPTIONAL, +# cenDsrcTollingZone CenDsrcTollingZone OPTIONAL +# } +# ------------------------------------------------------------------------------ Heading heading Speed speed diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg index 8f964674b..a5cdf6b04 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE BasicVehicleContainerLowFrequency +# --- ASN.1 Definition --------------------------------------------------------- +# BasicVehicleContainerLowFrequency ::= SEQUENCE { +# vehicleRole VehicleRole, +# exteriorLights ExteriorLights, +# pathHistory PathHistory +# } +# ------------------------------------------------------------------------------ VehicleRole vehicle_role ExteriorLights exterior_lights diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg index d83efd37f..c430f9ce8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CAM +# --- ASN.1 Definition --------------------------------------------------------- +# CAM ::= SEQUENCE { +# header ItsPduHeader, +# cam CoopAwareness +# } +# ------------------------------------------------------------------------------ # The root data frame for cooperative awareness messages ItsPduHeader header diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg index 124001ca4..19f45ad71 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg @@ -25,7 +25,15 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CamParameters .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CamParameters ::= SEQUENCE { +# basicContainer BasicContainer, +# highFrequencyContainer HighFrequencyContainer, +# lowFrequencyContainer LowFrequencyContainer OPTIONAL, +# specialVehicleContainer SpecialVehicleContainer OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ BasicContainer basic_container HighFrequencyContainer high_frequency_container diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg index 46fa8aed4..9260033c6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CauseCode .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CauseCode ::= SEQUENCE { +# causeCode CauseCodeType, +# subCauseCode SubCauseCodeType, +# ... +# } +# ------------------------------------------------------------------------------ CauseCodeType cause_code SubCauseCodeType sub_cause_code diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg index 61c553d96..c3034f85f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg @@ -25,7 +25,37 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER CauseCodeType +# --- ASN.1 Definition --------------------------------------------------------- +# CauseCodeType ::= INTEGER { +# reserved (0), +# trafficCondition (1), +# accident (2), +# roadworks (3), +# impassability (5), +# adverseWeatherCondition-Adhesion (6), +# aquaplannning (7), +# hazardousLocation-SurfaceCondition (9), +# hazardousLocation-ObstacleOnTheRoad (10), +# hazardousLocation-AnimalOnTheRoad (11), +# humanPresenceOnTheRoad (12), +# wrongWayDriving (14), +# rescueAndRecoveryWorkInProgress (15), +# adverseWeatherCondition-ExtremeWeatherCondition (17), +# adverseWeatherCondition-Visibility (18), +# adverseWeatherCondition-Precipitation (19), +# slowVehicle (26), +# dangerousEndOfQueue (27), +# vehicleBreakdown (91), +# postCrash (92), +# humanProblem (93), +# stationaryVehicle (94), +# emergencyVehicleApproaching (95), +# hazardousLocation-DangerousCurve (96), +# collisionRisk (97), +# signalViolation (98), +# dangerousSituation (99) +# } (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg index 96a17295f..cf12d0483 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CenDsrcTollingZone .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CenDsrcTollingZone ::= SEQUENCE { +# protectedZoneLatitude Latitude, +# protectedZoneLongitude Longitude, +# cenDsrcTollingZoneID CenDsrcTollingZoneID OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ Latitude protected_zone_latitude Longitude protected_zone_longitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg index 6fc8d1f81..dd12f6a75 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## TYPE-ALIAS CenDsrcTollingZoneID +# --- ASN.1 Definition --------------------------------------------------------- +# CenDsrcTollingZoneID ::= ProtectedZoneID +# ------------------------------------------------------------------------------ ProtectedZoneID value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg index 55b9c5f22..b4ff53fbf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ClosedLanes .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ClosedLanes ::= SEQUENCE { +# innerhardShoulderStatus HardShoulderStatus OPTIONAL, +# outerhardShoulderStatus HardShoulderStatus OPTIONAL, +# drivingLaneStatus DrivingLaneStatus OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ HardShoulderStatus innerhard_shoulder_status bool innerhard_shoulder_status_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg index a1439f329..088c70f41 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER CollisionRiskSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# CollisionRiskSubCauseCode ::= INTEGER {unavailable(0), longitudinalCollisionRisk(1), crossingCollisionRisk(2), lateralCollisionRisk(3), vulnerableRoadUser(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg index 518be360d..ea7c612ee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CoopAwareness +# --- ASN.1 Definition --------------------------------------------------------- +# CoopAwareness ::= SEQUENCE { +# generationDeltaTime GenerationDeltaTime, +# camParameters CamParameters +# } +# ------------------------------------------------------------------------------ GenerationDeltaTime generation_delta_time CamParameters cam_parameters diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg index 6aead5fdf..c9f50f1b2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Curvature +# --- ASN.1 Definition --------------------------------------------------------- +# Curvature ::= SEQUENCE { +# curvatureValue CurvatureValue, +# curvatureConfidence CurvatureConfidence +# } +# ------------------------------------------------------------------------------ CurvatureValue curvature_value CurvatureConfidence curvature_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg index b9e8e49d3..c7166a4dd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED CurvatureCalculationMode .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CurvatureCalculationMode ::= ENUMERATED {yawRateUsed(0), yawRateNotUsed(1), unavailable(2), ...} +# ------------------------------------------------------------------------------ uint8 value uint8 YAW_RATE_USED = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg index b36c4ea4d..014ac9603 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg @@ -25,7 +25,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED CurvatureConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# CurvatureConfidence ::= ENUMERATED { +# onePerMeter-0-00002 (0), +# onePerMeter-0-0001 (1), +# onePerMeter-0-0005 (2), +# onePerMeter-0-002 (3), +# onePerMeter-0-01 (4), +# onePerMeter-0-1 (5), +# outOfRange (6), +# unavailable (7) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 ONE_PER_METER_0_00002 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg index 1607dc28d..ebb64831c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER CurvatureValue +# --- ASN.1 Definition --------------------------------------------------------- +# CurvatureValue ::= INTEGER {straight(0), unavailable(1023)} (-1023..1023) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -1023 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index 9484263ff..5625ad6c4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DangerousEndOfQueueSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousEndOfQueueSubCauseCode ::= INTEGER {unavailable(0), suddenEndOfQueue(1), queueOverHill(2), queueAroundBend(3), queueInTunnel(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg index 9213942db..f49e5e2bc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg @@ -25,7 +25,30 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED DangerousGoodsBasic +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousGoodsBasic::= ENUMERATED { +# explosives1(0), +# explosives2(1), +# explosives3(2), +# explosives4(3), +# explosives5(4), +# explosives6(5), +# flammableGases(6), +# nonFlammableGases(7), +# toxicGases(8), +# flammableLiquids(9), +# flammableSolids(10), +# substancesLiableToSpontaneousCombustion(11), +# substancesEmittingFlammableGasesUponContactWithWater(12), +# oxidizingSubstances(13), +# organicPeroxides(14), +# toxicSubstances(15), +# infectiousSubstances(16), +# radioactiveMaterial(17), +# corrosiveSubstances(18), +# miscellaneousDangerousSubstances(19) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 EXPLOSIVES_1 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg index 6ac877f17..a2c6c2048 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg @@ -25,6 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DangerousGoodsContainer +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousGoodsContainer ::= SEQUENCE { +# dangerousGoodsBasic DangerousGoodsBasic +# } +# ------------------------------------------------------------------------------ DangerousGoodsBasic dangerous_goods_basic diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg index 91afc5574..38e4e4c18 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg @@ -25,7 +25,19 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DangerousGoodsExtended .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousGoodsExtended ::= SEQUENCE { +# dangerousGoodsType DangerousGoodsBasic, +# unNumber INTEGER (0..9999), +# elevatedTemperature BOOLEAN, +# tunnelsRestricted BOOLEAN, +# limitedQuantity BOOLEAN, +# emergencyActionCode IA5String (SIZE (1..24)) OPTIONAL, +# phoneNumber PhoneNumber OPTIONAL, +# companyName UTF8String (SIZE (1..24)) OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ DangerousGoodsBasic dangerous_goods_type uint16 un_number diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg index 52ec15222..ff8f082b4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DangerousSituationSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousSituationSubCauseCode ::= INTEGER {unavailable(0), emergencyElectronicBrakeEngaged(1), preCrashSystemEngaged(2), espEngaged(3), absEngaged(4), aebEngaged(5), brakeWarningEngaged(6), collisionRiskWarningEngaged(7)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg index 19e2b4ffd..42e3c7d66 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DeltaAltitude +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaAltitude ::= INTEGER {oneCentimeterUp (1), oneCentimeterDown (-1), unavailable(12800)} (-12700..12800) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -12700 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg index b9977f0d4..8316b7c49 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DeltaLatitude +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaLatitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10) , unavailable(131072)} (-131071..131072) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -131071 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg index 73d04ec5a..001a1fa12 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DeltaLongitude +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaLongitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(131072)} (-131071..131072) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -131071 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg index 7ae8cd306..fd91f916d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DeltaReferencePosition +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaReferencePosition ::= SEQUENCE { +# deltaLatitude DeltaLatitude, +# deltaLongitude DeltaLongitude, +# deltaAltitude DeltaAltitude +# } +# ------------------------------------------------------------------------------ DeltaLatitude delta_latitude DeltaLongitude delta_longitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg index d67682243..9b9b8097a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF DigitalMap +# --- ASN.1 Definition --------------------------------------------------------- +# DigitalMap ::= SEQUENCE (SIZE(1..256)) OF ReferencePosition +# ------------------------------------------------------------------------------ ReferencePosition[] array uint16 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg index 2d1c95e2a..75d1f4936 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED DriveDirection +# --- ASN.1 Definition --------------------------------------------------------- +# DriveDirection ::= ENUMERATED {forward (0), backward (1), unavailable (2)} +# ------------------------------------------------------------------------------ uint8 value uint8 FORWARD = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg index 43ea6ca1c..f55056461 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING DrivingLaneStatus +# --- ASN.1 Definition --------------------------------------------------------- +# DrivingLaneStatus ::= BIT STRING (SIZE (1..13)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg index b52eb16db..6459d3da9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BOOLEAN EmbarkationStatus +# --- ASN.1 Definition --------------------------------------------------------- +# EmbarkationStatus ::= BOOLEAN +# ------------------------------------------------------------------------------ bool value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg index 3be9e58ee..b75278ae1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE EmergencyContainer +# --- ASN.1 Definition --------------------------------------------------------- +# EmergencyContainer ::= SEQUENCE { +# lightBarSirenInUse LightBarSirenInUse, +# incidentIndication CauseCode OPTIONAL, +# emergencyPriority EmergencyPriority OPTIONAL +# } +# ------------------------------------------------------------------------------ LightBarSirenInUse light_bar_siren_in_use CauseCode incident_indication diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg index d9a335ed9..fec313c25 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING EmergencyPriority +# --- ASN.1 Definition --------------------------------------------------------- +# EmergencyPriority ::= BIT STRING {requestForRightOfWay(0), requestForFreeCrossingAtATrafficLight(1)} (SIZE(2)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 33eb4fbbd..119607ee3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER EmergencyVehicleApproachingSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# EmergencyVehicleApproachingSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicleApproaching(1), prioritizedVehicleApproaching(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg index ffdd50c96..c8d184879 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING EnergyStorageType +# --- ASN.1 Definition --------------------------------------------------------- +# EnergyStorageType ::= BIT STRING {hydrogenStorage(0), electricEnergyStorage(1), liquidPropaneGas(2), compressedNaturalGas(3), diesel(4), gasoline(5), ammonia(6)} (SIZE(7)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg index 6cc1045b6..7171933f8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF EventHistory +# --- ASN.1 Definition --------------------------------------------------------- +# EventHistory::= SEQUENCE (SIZE(1..23)) OF EventPoint +# ------------------------------------------------------------------------------ EventPoint[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg index c0fcc5bae..4514b8d6b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE EventPoint +# --- ASN.1 Definition --------------------------------------------------------- +# EventPoint ::= SEQUENCE { +# eventPosition DeltaReferencePosition, +# eventDeltaTime PathDeltaTime OPTIONAL, +# informationQuality InformationQuality +# } +# ------------------------------------------------------------------------------ DeltaReferencePosition event_position PathDeltaTime event_delta_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg index 77a240fb1..bf1abac96 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg @@ -25,7 +25,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING ExteriorLights +# --- ASN.1 Definition --------------------------------------------------------- +# ExteriorLights ::= BIT STRING { +# lowBeamHeadlightsOn (0), +# highBeamHeadlightsOn (1), +# leftTurnSignalOn (2), +# rightTurnSignalOn (3), +# daytimeRunningLightsOn (4), +# reverseLightOn (5), +# fogLightOn (6), +# parkingLightsOn (7) +# } (SIZE(8)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg index a790e6432..afd9c27d9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER GenerationDeltaTime +# --- ASN.1 Definition --------------------------------------------------------- +# GenerationDeltaTime ::= INTEGER { oneMilliSec(1) } (0..65535) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg index e19c27a02..b829dcda2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED HardShoulderStatus +# --- ASN.1 Definition --------------------------------------------------------- +# HardShoulderStatus ::= ENUMERATED {availableForStopping(0), closed(1), availableForDriving(2)} +# ------------------------------------------------------------------------------ uint8 value uint8 AVAILABLE_FOR_STOPPING = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 762fd771a..4766634a3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-AnimalOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), wildAnimals(1), herdOfAnimals(2), smallAnimals(3), largeAnimals(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index ff1002498..02551d9e1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationDangerousCurveSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-DangerousCurveSubCauseCode ::= INTEGER {unavailable(0), dangerousLeftTurnCurve(1), dangerousRightTurnCurve(2), multipleCurvesStartingWithUnknownTurningDirection(3), multipleCurvesStartingWithLeftTurn(4), multipleCurvesStartingWithRightTurn(5)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index aff6952f3..d0eee3f2e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-ObstacleOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), shedLoad(1), partsOfVehicles(2), partsOfTyres(3), bigObjects(4), fallenTrees(5), hubCaps(6), waitingVehicles(7)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 5b1536bee..4e147ca9d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationSurfaceConditionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-SurfaceConditionSubCauseCode ::= INTEGER {unavailable(0), rockfalls(1), earthquakeDamage(2), sewerCollapse(3), subsidence(4), snowDrifts(5), stormDamage(6), burstPipe(7), volcanoEruption(8), fallingIce(9)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg index 961b9a6c6..79915064f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Heading +# --- ASN.1 Definition --------------------------------------------------------- +# Heading ::= SEQUENCE { +# headingValue HeadingValue, +# headingConfidence HeadingConfidence +# } +# ------------------------------------------------------------------------------ HeadingValue heading_value HeadingConfidence heading_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg index 18b074792..e449a7d2a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HeadingConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# HeadingConfidence ::= INTEGER {equalOrWithinZeroPointOneDegree (1), equalOrWithinOneDegree (10), outOfRange(126), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg index bf95b1054..01ecf4177 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HeadingValue +# --- ASN.1 Definition --------------------------------------------------------- +# HeadingValue ::= INTEGER {wgs84North(0), wgs84East(900), wgs84South(1800), wgs84West(2700), unavailable(3601)} (0..3601) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg index 6456533de..a57e51b95 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HeightLonCarr +# --- ASN.1 Definition --------------------------------------------------------- +# HeightLonCarr ::= INTEGER {oneCentimeter(1), unavailable(100)} (1..100) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg index d278ab9b1..fe78d1406 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## CHOICE HighFrequencyContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# HighFrequencyContainer ::= CHOICE { +# basicVehicleContainerHighFrequency BasicVehicleContainerHighFrequency, +# rsuContainerHighFrequency RSUContainerHighFrequency, +# ... +# } +# ------------------------------------------------------------------------------ uint8 choice BasicVehicleContainerHighFrequency basic_vehicle_container_high_frequency diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 879b64b81..a59935c0a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HumanPresenceOnTheRoadSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HumanPresenceOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), childrenOnRoadway(1), cyclistOnRoadway(2), motorcyclistOnRoadway(3)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg index 3a91e85c7..50d2c72b9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HumanProblemSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HumanProblemSubCauseCode ::= INTEGER {unavailable(0), glycemiaProblem(1), heartProblem(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg index bd50329f8..aaa05b44b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER InformationQuality +# --- ASN.1 Definition --------------------------------------------------------- +# InformationQuality ::= INTEGER {unavailable(0), lowest(1), highest(7)} (0..7) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg index 4b62379b8..cba1ae5eb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF ItineraryPath +# --- ASN.1 Definition --------------------------------------------------------- +# ItineraryPath ::= SEQUENCE SIZE(1..40) OF ReferencePosition +# ------------------------------------------------------------------------------ ReferencePosition[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg index 16d132739..f7a6a34b0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg @@ -25,7 +25,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ItsPduHeader +# --- ASN.1 Definition --------------------------------------------------------- +# ItsPduHeader ::= SEQUENCE { +# protocolVersion INTEGER (0..255), +# messageID INTEGER{ denm(1), cam(2), poi(3), spatem(4), mapem(5), ivim(6), ev-rsr(7), tistpgtransaction(8), srem(9), ssem(10), evcsn(11), saem(12), rtcmem(13) } (0..255), -- Mantis #7209, #7005 +# ------------------------------------------------------------------------------ uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 uint8 PROTOCOL_VERSION_MAX = 255 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg index 14b6304e1..cf2c4184e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg @@ -25,7 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER LanePosition +# --- ASN.1 Definition --------------------------------------------------------- +# LanePosition::= INTEGER {offTheRoad(-1), hardShoulder(0), +# outermostDrivingLane(1), secondLaneFromOutside(2)} (-1..14) +# ------------------------------------------------------------------------------ int8 value int8 MIN = -1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg index 8a7b7678d..3e2f5d914 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE LateralAcceleration +# --- ASN.1 Definition --------------------------------------------------------- +# LateralAcceleration ::= SEQUENCE { +# lateralAccelerationValue LateralAccelerationValue, +# lateralAccelerationConfidence AccelerationConfidence +# } +# ------------------------------------------------------------------------------ LateralAccelerationValue lateral_acceleration_value AccelerationConfidence lateral_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg index ff380dc60..c0c95cdf3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER LateralAccelerationValue +# --- ASN.1 Definition --------------------------------------------------------- +# LateralAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredToRight(-1), pointOneMeterPerSecSquaredToLeft(1), unavailable(161)} (-160 .. 161) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -160 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg index c7cd97580..d6790b6a7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER Latitude +# --- ASN.1 Definition --------------------------------------------------------- +# Latitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10), unavailable(900000001)} (-900000000..900000001) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -900000000 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg index b58c05ebb..af41f3d23 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING LightBarSirenInUse +# --- ASN.1 Definition --------------------------------------------------------- +# LightBarSirenInUse ::= BIT STRING { +# lightBarActivated (0), +# sirenActivated (1) +# } (SIZE(2)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg index 341e21778..0d881d795 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER Longitude +# --- ASN.1 Definition --------------------------------------------------------- +# Longitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(1800000001)} (-1800000000..1800000001) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -1800000000 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg index 4880b8e99..f8ce9be22 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE LongitudinalAcceleration +# --- ASN.1 Definition --------------------------------------------------------- +# LongitudinalAcceleration ::= SEQUENCE { +# longitudinalAccelerationValue LongitudinalAccelerationValue, +# longitudinalAccelerationConfidence AccelerationConfidence +# } +# ------------------------------------------------------------------------------ LongitudinalAccelerationValue longitudinal_acceleration_value AccelerationConfidence longitudinal_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg index e5e387119..5490b1049 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER LongitudinalAccelerationValue +# --- ASN.1 Definition --------------------------------------------------------- +# LongitudinalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredForward(1), pointOneMeterPerSecSquaredBackward(-1), unavailable(161)} (-160 .. 161) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -160 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg index 973ebcabc..26667688c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## CHOICE LowFrequencyContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# LowFrequencyContainer ::= CHOICE { +# basicVehicleContainerLowFrequency BasicVehicleContainerLowFrequency, +# ... +# } +# ------------------------------------------------------------------------------ uint8 choice BasicVehicleContainerLowFrequency basic_vehicle_container_low_frequency diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg index 09d9ceb5c..29866b9b5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER NumberOfOccupants +# --- ASN.1 Definition --------------------------------------------------------- +# NumberOfOccupants ::= INTEGER {oneOccupant (1), unavailable(127)} (0 .. 127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg index ea4ca5882..ed47dd83f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## Utf8String OpeningDaysHours +# --- ASN.1 Definition --------------------------------------------------------- +# OpeningDaysHours ::= UTF8String +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg index f95b5adbc..eb535a512 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PathDeltaTime +# --- ASN.1 Definition --------------------------------------------------------- +# PathDeltaTime ::= INTEGER {tenMilliSecondsInPast(1)} (1..65535, ...) +# ------------------------------------------------------------------------------ int64 value int64 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg index 9a72d15bc..a01230954 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF PathHistory +# --- ASN.1 Definition --------------------------------------------------------- +# PathHistory::= SEQUENCE (SIZE(0..40)) OF PathPoint +# ------------------------------------------------------------------------------ PathPoint[] array uint8 MIN_SIZE = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg index 87ce1b575..beb29a984 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PathPoint +# --- ASN.1 Definition --------------------------------------------------------- +# PathPoint ::= SEQUENCE { +# pathPosition DeltaReferencePosition, +# pathDeltaTime PathDeltaTime OPTIONAL +# } +# ------------------------------------------------------------------------------ DeltaReferencePosition path_position PathDeltaTime path_delta_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg index 5e2f9a67f..5e647048f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PerformanceClass +# --- ASN.1 Definition --------------------------------------------------------- +# PerformanceClass ::= INTEGER {unavailable(0), performanceClassA(1), performanceClassB(2)} (0..7) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg index 87c284302..4406676ab 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## NumericString PhoneNumber +# --- ASN.1 Definition --------------------------------------------------------- +# PhoneNumber ::= NumericString (SIZE(1..16)) +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg index 18bb04a98..eb542bcf9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosCentMass +# --- ASN.1 Definition --------------------------------------------------------- +# PosCentMass ::= INTEGER {tenCentimeters(1), unavailable(63)} (1..63) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg index aeb665ecc..69e6be2a2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PosConfidenceEllipse +# --- ASN.1 Definition --------------------------------------------------------- +# PosConfidenceEllipse ::= SEQUENCE { +# semiMajorConfidence SemiAxisLength, +# semiMinorConfidence SemiAxisLength, +# semiMajorOrientation HeadingValue +# } +# ------------------------------------------------------------------------------ SemiAxisLength semi_major_confidence SemiAxisLength semi_minor_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg index 8cfd73ba9..dec614584 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosFrontAx +# --- ASN.1 Definition --------------------------------------------------------- +# PosFrontAx ::= INTEGER {tenCentimeters(1), unavailable(20)} (1..20) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg index 5efdc3d90..56a23793c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosLonCarr +# --- ASN.1 Definition --------------------------------------------------------- +# PosLonCarr ::= INTEGER {oneCentimeter(1), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg index 6294ffc82..f000268e6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosPillar +# --- ASN.1 Definition --------------------------------------------------------- +# PosPillar ::= INTEGER {tenCentimeters(1), unavailable(30)} (1..30) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg index 72347aba9..bab7e4e92 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg @@ -25,7 +25,29 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING PositionOfOccupants +# --- ASN.1 Definition --------------------------------------------------------- +# PositionOfOccupants ::= BIT STRING { +# row1LeftOccupied (0), +# row1RightOccupied (1), +# row1MidOccupied (2), +# row1NotDetectable (3), +# row1NotPresent (4), +# row2LeftOccupied (5), +# row2RightOccupied (6), +# row2MidOccupied (7), +# row2NotDetectable (8), +# row2NotPresent (9), +# row3LeftOccupied (10), +# row3RightOccupied (11), +# row3MidOccupied (12), +# row3NotDetectable (13), +# row3NotPresent (14), +# row4LeftOccupied (15), +# row4RightOccupied (16), +# row4MidOccupied (17), +# row4NotDetectable (18), +# row4NotPresent (19)} (SIZE(20)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg index 824502493..7db286c34 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF PositionOfPillars +# --- ASN.1 Definition --------------------------------------------------------- +# PositionOfPillars ::= SEQUENCE (SIZE(1..3, ...)) OF PosPillar +# ------------------------------------------------------------------------------ PosPillar[] array int64 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg index aad52eeb7..1032ae4b1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED PositioningSolutionType .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# PositioningSolutionType ::= ENUMERATED {noPositioningSolution(0), sGNSS(1), dGNSS(2), sGNSSplusDR(3), dGNSSplusDR(4), dR(5), ...} +# ------------------------------------------------------------------------------ uint8 value uint8 NO_POSITIONING_SOLUTION = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg index 5dabb7149..85a35798a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PostCrashSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# PostCrashSubCauseCode ::= INTEGER {unavailable(0), accidentWithoutECallTriggered (1), accidentWithECallManuallyTriggered (2), accidentWithECallAutomaticallyTriggered (3), accidentWithECallTriggeredWithoutAccessToCellularNetwork(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg index d8ac4b043..d1335c7cc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg @@ -25,7 +25,17 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ProtectedCommunicationZone .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedCommunicationZone ::= SEQUENCE { +# protectedZoneType ProtectedZoneType, +# expiryTime TimestampIts OPTIONAL, +# protectedZoneLatitude Latitude, +# protectedZoneLongitude Longitude, +# protectedZoneRadius ProtectedZoneRadius OPTIONAL, +# protectedZoneID ProtectedZoneID OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ ProtectedZoneType protected_zone_type TimestampIts expiry_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg index 43650b6c2..2d5f9f9a4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF ProtectedCommunicationZonesRSU +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedCommunicationZonesRSU ::= SEQUENCE (SIZE(1..16)) OF ProtectedCommunicationZone +# ------------------------------------------------------------------------------ ProtectedCommunicationZone[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg index ae4c41709..bb4f93c32 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER ProtectedZoneID +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedZoneID ::= INTEGER (0.. 134217727) +# ------------------------------------------------------------------------------ uint32 value uint32 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg index adf686ea1..97a3ead2e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER ProtectedZoneRadius +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedZoneRadius ::= INTEGER {oneMeter(1)} (1..255,...) +# ------------------------------------------------------------------------------ int64 value int64 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg index 812c608d7..9ba419cec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED ProtectedZoneType .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedZoneType::= ENUMERATED { permanentCenDsrcTolling (0), ..., temporaryCenDsrcTolling (1) } +# ------------------------------------------------------------------------------ uint8 value uint8 PERMANENT_CEN_DSRC_TOLLING = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg index f6fdbe3ea..32c276aa5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PtActivation +# --- ASN.1 Definition --------------------------------------------------------- +# PtActivation ::= SEQUENCE { +# ptActivationType PtActivationType, +# ptActivationData PtActivationData +# } +# ------------------------------------------------------------------------------ PtActivationType pt_activation_type PtActivationData pt_activation_data diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg index 9e0108cdf..f0da8da3a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg @@ -1,3 +1,5 @@ -## OCTET-STRING PtActivationData +# --- ASN.1 Definition --------------------------------------------------------- +# PtActivationData ::= OCTET STRING (SIZE(1..20)) +# ------------------------------------------------------------------------------ uint8[] value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg index 16c038fa4..1d3a14412 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PtActivationType +# --- ASN.1 Definition --------------------------------------------------------- +# PtActivationType ::= INTEGER {undefinedCodingType(0), r09-16CodingType(1), vdv-50149CodingType(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg index 99d897d78..109418c87 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PublicTransportContainer +# --- ASN.1 Definition --------------------------------------------------------- +# PublicTransportContainer ::= SEQUENCE { +# embarkationStatus EmbarkationStatus, +# ptActivation PtActivation OPTIONAL +# } +# ------------------------------------------------------------------------------ EmbarkationStatus embarkation_status PtActivation pt_activation diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg index 3e64de180..61c0ce7ec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE RSUContainerHighFrequency .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# RSUContainerHighFrequency ::= SEQUENCE { +# protectedCommunicationZonesRSU ProtectedCommunicationZonesRSU OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ ProtectedCommunicationZonesRSU protected_communication_zones_rsu bool protected_communication_zones_rsu_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg index 07a4e8e6d..738b78443 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ReferencePosition +# --- ASN.1 Definition --------------------------------------------------------- +# ReferencePosition ::= SEQUENCE { +# latitude Latitude, +# longitude Longitude, +# positionConfidenceEllipse PosConfidenceEllipse , +# altitude Altitude +# } +# ------------------------------------------------------------------------------ Latitude latitude Longitude longitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg index 443ca5e6f..4bdc9a00c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RelevanceDistance +# --- ASN.1 Definition --------------------------------------------------------- +# RelevanceDistance ::= ENUMERATED {lessThan50m(0), lessThan100m(1), lessThan200m(2), lessThan500m(3), lessThan1000m(4), lessThan5km(5), lessThan10km(6), over10km(7)} +# ------------------------------------------------------------------------------ uint8 value uint8 LESS_THAN_50M = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg index 867fa1853..23849c372 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RelevanceTrafficDirection +# --- ASN.1 Definition --------------------------------------------------------- +# RelevanceTrafficDirection ::= ENUMERATED {allTrafficDirections(0), upstreamTraffic(1), downstreamTraffic(2), oppositeTraffic(3)} +# ------------------------------------------------------------------------------ uint8 value uint8 ALL_TRAFFIC_DIRECTIONS = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg index 856dfe2fb..7a88dc8db 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RequestResponseIndication +# --- ASN.1 Definition --------------------------------------------------------- +# RequestResponseIndication ::= ENUMERATED {request(0), response(1)} +# ------------------------------------------------------------------------------ uint8 value uint8 REQUEST = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index aed759dcc..427e20f40 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# RescueAndRecoveryWorkInProgressSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicles(1), rescueHelicopterLanding(2), policeActivityOngoing(3), medicalEmergencyOngoing(4), childAbductionInProgress(5)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg index 818dd2f51..e4be99071 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg @@ -25,6 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE RescueContainer +# --- ASN.1 Definition --------------------------------------------------------- +# RescueContainer ::= SEQUENCE { +# lightBarSirenInUse LightBarSirenInUse +# } +# ------------------------------------------------------------------------------ LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg index ebdb78e61..f9c80d5be 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF RestrictedTypes +# --- ASN.1 Definition --------------------------------------------------------- +# RestrictedTypes ::= SEQUENCE (SIZE(1..3, ...)) OF StationType +# ------------------------------------------------------------------------------ StationType[] array int64 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg index 7ab57d5c2..7280b7c6b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RoadType +# --- ASN.1 Definition --------------------------------------------------------- +# RoadType ::= ENUMERATED { +# urban-NoStructuralSeparationToOppositeLanes(0), +# urban-WithStructuralSeparationToOppositeLanes(1), +# nonUrban-NoStructuralSeparationToOppositeLanes(2), +# nonUrban-WithStructuralSeparationToOppositeLanes(3)} +# ------------------------------------------------------------------------------ uint8 value uint8 URBAN_NO_STRUCTURAL_SEPARATION_TO_OPPOSITE_LANES = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg index d9e2fe03f..3525a2c3e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE RoadWorksContainerBasic +# --- ASN.1 Definition --------------------------------------------------------- +# RoadWorksContainerBasic ::= SEQUENCE { +# roadworksSubCauseCode RoadworksSubCauseCode OPTIONAL, +# lightBarSirenInUse LightBarSirenInUse, +# closedLanes ClosedLanes OPTIONAL +# } +# ------------------------------------------------------------------------------ RoadworksSubCauseCode roadworks_sub_cause_code bool roadworks_sub_cause_code_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg index 1b12c35e4..017a34d21 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER RoadworksSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# RoadworksSubCauseCode ::= INTEGER {unavailable(0), majorRoadworks(1), roadMarkingWork(2), slowMovingRoadMaintenance(3), shortTermStationaryRoadworks(4), streetCleaning(5), winterService(6)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg index b419536e9..3ac82382a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE SafetyCarContainer +# --- ASN.1 Definition --------------------------------------------------------- +# SafetyCarContainer ::= SEQUENCE { +# lightBarSirenInUse LightBarSirenInUse, +# incidentIndication CauseCode OPTIONAL, +# trafficRule TrafficRule OPTIONAL, +# speedLimit SpeedLimit OPTIONAL +# } +# ------------------------------------------------------------------------------ LightBarSirenInUse light_bar_siren_in_use CauseCode incident_indication diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg index c4c1c38ec..fbd569ec1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SemiAxisLength +# --- ASN.1 Definition --------------------------------------------------------- +# SemiAxisLength ::= INTEGER{oneCentimeter(1), outOfRange(4094), unavailable(4095)} (0..4095) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg index 27a36a32c..8fd8be07e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SequenceNumber +# --- ASN.1 Definition --------------------------------------------------------- +# SequenceNumber ::= INTEGER (0..65535) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg index bb8a3c386..6286201a3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SignalViolationSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# SignalViolationSubCauseCode ::= INTEGER {unavailable(0), stopSignViolation(1), trafficLightViolation(2), turningRegulationViolation(3)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg index faf4093de..ffc371dec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SlowVehicleSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# SlowVehicleSubCauseCode ::= INTEGER {unavailable(0), maintenanceVehicle(1), vehiclesSlowingToLookAtAccident(2), abnormalLoad(3), abnormalWideLoad(4), convoy(5), snowplough(6), deicing(7), saltingVehicles(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg index 2b4b21c05..e1c057461 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE SpecialTransportContainer +# --- ASN.1 Definition --------------------------------------------------------- +# SpecialTransportContainer ::= SEQUENCE { +# specialTransportType SpecialTransportType, +# lightBarSirenInUse LightBarSirenInUse +# } +# ------------------------------------------------------------------------------ SpecialTransportType special_transport_type LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg index 8444a35ea..7bfb3f184 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING SpecialTransportType +# --- ASN.1 Definition --------------------------------------------------------- +# SpecialTransportType ::= BIT STRING {heavyLoad(0), excessWidth(1), excessLength(2), excessHeight(3)} (SIZE(4)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg index c3c2bd971..3ca723811 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg @@ -25,7 +25,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## CHOICE SpecialVehicleContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# SpecialVehicleContainer ::= CHOICE { +# publicTransportContainer PublicTransportContainer, +# specialTransportContainer SpecialTransportContainer, +# dangerousGoodsContainer DangerousGoodsContainer, +# roadWorksContainerBasic RoadWorksContainerBasic, +# rescueContainer RescueContainer, +# emergencyContainer EmergencyContainer, +# safetyCarContainer SafetyCarContainer, +# ... +# } +# ------------------------------------------------------------------------------ uint8 choice PublicTransportContainer public_transport_container diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg index f603b1dcc..e6a686f59 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Speed +# --- ASN.1 Definition --------------------------------------------------------- +# Speed ::= SEQUENCE { +# speedValue SpeedValue, +# speedConfidence SpeedConfidence +# } +# ------------------------------------------------------------------------------ SpeedValue speed_value SpeedConfidence speed_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg index 930449281..3001fa3f3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SpeedConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# SpeedConfidence ::= INTEGER {equalOrWithinOneCentimeterPerSec(1), equalOrWithinOneMeterPerSec(100), outOfRange(126), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg index 3fd12e847..5eb6c64c4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SpeedLimit +# --- ASN.1 Definition --------------------------------------------------------- +# SpeedLimit ::= INTEGER {oneKmPerHour(1)} (1..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg index 9617fb469..978abe6e5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SpeedValue +# --- ASN.1 Definition --------------------------------------------------------- +# SpeedValue ::= INTEGER {standstill(0), oneCentimeterPerSec(1), unavailable(16383)} (0..16383) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg index 9e5dc24dd..6cf2e47dc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER StationID +# --- ASN.1 Definition --------------------------------------------------------- +# StationID ::= INTEGER(0..4294967295) +# ------------------------------------------------------------------------------ uint32 value uint32 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg index 82a3cc1ea..d84cf4192 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg @@ -25,7 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER StationType +# --- ASN.1 Definition --------------------------------------------------------- +# StationType ::= INTEGER {unknown(0), pedestrian(1), cyclist(2), moped(3), motorcycle(4), passengerCar(5), bus(6), +# lightTruck(7), heavyTruck(8), trailer(9), specialVehicles(10), tram(11), roadSideUnit(15)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg index a35450fd1..6cd027626 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED StationarySince +# --- ASN.1 Definition --------------------------------------------------------- +# StationarySince ::= ENUMERATED {lessThan1Minute(0), lessThan2Minutes(1), lessThan15Minutes(2), equalOrGreater15Minutes(3)} +# ------------------------------------------------------------------------------ uint8 value uint8 LESS_THAN_1_MINUTE = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg index 108080973..a970bdcb5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER StationaryVehicleSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# StationaryVehicleSubCauseCode ::= INTEGER {unavailable(0), humanProblem(1), vehicleBreakdown(2), postCrash(3), publicTransportStop(4), carryingDangerousGoods(5)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg index b38f81f0d..eb08c754b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE SteeringWheelAngle +# --- ASN.1 Definition --------------------------------------------------------- +# SteeringWheelAngle ::= SEQUENCE { +# steeringWheelAngleValue SteeringWheelAngleValue, +# steeringWheelAngleConfidence SteeringWheelAngleConfidence +# } +# ------------------------------------------------------------------------------ SteeringWheelAngleValue steering_wheel_angle_value SteeringWheelAngleConfidence steering_wheel_angle_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg index 7c3d46b9a..9c07b52b0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SteeringWheelAngleConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# SteeringWheelAngleConfidence ::= INTEGER {equalOrWithinOnePointFiveDegree (1), outOfRange(126), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg index c50be3980..aeae3ce54 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SteeringWheelAngleValue +# --- ASN.1 Definition --------------------------------------------------------- +# SteeringWheelAngleValue ::= INTEGER {straight(0), onePointFiveDegreesToRight(-1), onePointFiveDegreesToLeft(1), unavailable(512)} (-511..512) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -511 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg index 305bb683a..ebc0b6600 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SubCauseCodeType +# --- ASN.1 Definition --------------------------------------------------------- +# SubCauseCodeType ::= INTEGER (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg index 09dc259a9..0a3e27072 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER Temperature +# --- ASN.1 Definition --------------------------------------------------------- +# Temperature ::= INTEGER {equalOrSmallerThanMinus60Deg (-60), oneDegreeCelsius(1), equalOrGreaterThan67Deg(67)} (-60..67) +# ------------------------------------------------------------------------------ int8 value int8 MIN = -60 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg index d8a0429ed..8366db355 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TimestampIts +# --- ASN.1 Definition --------------------------------------------------------- +# TimestampIts ::= INTEGER {utcStartOf2004(0), oneMillisecAfterUTCStartOf2004(1)} (0..4398046511103) +# ------------------------------------------------------------------------------ uint64 value uint64 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg index 5f5504458..f3a2e2a48 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF Traces +# --- ASN.1 Definition --------------------------------------------------------- +# Traces ::= SEQUENCE SIZE(1..7) OF PathHistory +# ------------------------------------------------------------------------------ PathHistory[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg index bf5bd835c..41b2503eb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TrafficConditionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# TrafficConditionSubCauseCode ::= INTEGER {unavailable(0), increasedVolumeOfTraffic(1), trafficJamSlowlyIncreasing(2), trafficJamIncreasing(3), trafficJamStronglyIncreasing(4), trafficStationary(5), trafficJamSlightlyDecreasing(6), trafficJamDecreasing(7), trafficJamStronglyDecreasing(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg index 381da7c71..c688d0470 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg @@ -25,7 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED TrafficRule .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# TrafficRule ::= ENUMERATED {noPassing(0), noPassingForTrucks(1), passToRight(2), passToLeft(3), ... +# } +# ------------------------------------------------------------------------------ uint8 value uint8 NO_PASSING = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg index a7edb7d27..e2f87591d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TransmissionInterval +# --- ASN.1 Definition --------------------------------------------------------- +# TransmissionInterval ::= INTEGER {oneMilliSecond(1), tenSeconds(10000)} (1..10000) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg index abab38688..510f64696 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TurningRadius +# --- ASN.1 Definition --------------------------------------------------------- +# TurningRadius ::= INTEGER {point4Meters(1), unavailable(255)} (1..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg index 2a19a755b..6d5226ba7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## Ia5String VDS +# --- ASN.1 Definition --------------------------------------------------------- +# VDS ::= IA5String (SIZE(6)) +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg index a1c798831..9e069e511 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER ValidityDuration +# --- ASN.1 Definition --------------------------------------------------------- +# ValidityDuration ::= INTEGER {timeOfDetection(0), oneSecondAfterDetection(1)} (0..86400) +# ------------------------------------------------------------------------------ uint32 value uint32 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg index 1b76f5b68..814d2276a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleBreakdownSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleBreakdownSubCauseCode ::= INTEGER {unavailable(0), lackOfFuel (1), lackOfBatteryPower (2), engineProblem(3), transmissionProblem(4), engineCoolingProblem(5), brakingSystemProblem(6), steeringProblem(7), tyrePuncture(8), tyrePressureProblem(9)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg index ce86ece17..e43ea5841 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE VehicleIdentification .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleIdentification ::= SEQUENCE { +# wMInumber WMInumber OPTIONAL, +# vDS VDS OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ WMInumber w_m_inumber bool w_m_inumber_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg index 0efac770f..0b68fb8ef 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE VehicleLength +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleLength ::= SEQUENCE { +# vehicleLengthValue VehicleLengthValue, +# vehicleLengthConfidenceIndication VehicleLengthConfidenceIndication +# } +# ------------------------------------------------------------------------------ VehicleLengthValue vehicle_length_value VehicleLengthConfidenceIndication vehicle_length_confidence_indication diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg index b74b2519a..5b5d5d4c7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED VehicleLengthConfidenceIndication +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleLengthConfidenceIndication ::= ENUMERATED {noTrailerPresent(0), trailerPresentWithKnownLength(1), trailerPresentWithUnknownLength(2), trailerPresenceIsUnknown(3), unavailable(4)} +# ------------------------------------------------------------------------------ uint8 value uint8 NO_TRAILER_PRESENT = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg index 727323452..baed0b1ee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleLengthValue +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleLengthValue ::= INTEGER {tenCentimeters(1), outOfRange(1022), unavailable(1023)} (1..1023) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg index d849f7995..986aab8fc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleMass +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleMass ::= INTEGER {hundredKg(1), unavailable(1024)} (1..1024) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg index c8aac5c89..3e089a89a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED VehicleRole +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleRole ::= ENUMERATED {default(0), publicTransport(1), specialTransport(2), dangerousGoods(3), roadWork(4), rescue(5), emergency(6), safetyCar(7), agriculture(8), commercial(9), military(10), roadOperator(11), taxi(12), reserved1(13), reserved2(14), reserved3(15)} +# ------------------------------------------------------------------------------ uint8 value uint8 DEFAULT = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg index a3f87bd07..b0a8e7fa5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleWidth +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleWidth ::= INTEGER {tenCentimeters(1), outOfRange(61), unavailable(62)} (1..62) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg index 51e0d5979..0ac4bda1a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE VerticalAcceleration +# --- ASN.1 Definition --------------------------------------------------------- +# VerticalAcceleration ::= SEQUENCE { +# verticalAccelerationValue VerticalAccelerationValue, +# verticalAccelerationConfidence AccelerationConfidence +# } +# ------------------------------------------------------------------------------ VerticalAccelerationValue vertical_acceleration_value AccelerationConfidence vertical_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg index 4a7a480e6..f0abb220c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VerticalAccelerationValue +# --- ASN.1 Definition --------------------------------------------------------- +# VerticalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredUp(1), pointOneMeterPerSecSquaredDown(-1), unavailable(161)} (-160 .. 161) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -160 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg index 4f15b48b3..072b549a6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## Ia5String WMInumber +# --- ASN.1 Definition --------------------------------------------------------- +# WMInumber ::= IA5String (SIZE(1..3)) +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg index 89fdb9ad3..0b7a691a5 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER WheelBaseVehicle +# --- ASN.1 Definition --------------------------------------------------------- +# WheelBaseVehicle ::= INTEGER {tenCentimeters(1), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg index 900dbc587..a4611cb8c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER WrongWayDrivingSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# WrongWayDrivingSubCauseCode ::= INTEGER {unavailable(0), wrongLane(1), wrongDirection(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg index 404b07465..7305b6027 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE YawRate +# --- ASN.1 Definition --------------------------------------------------------- +# YawRate::= SEQUENCE { +# yawRateValue YawRateValue, +# yawRateConfidence YawRateConfidence +# } +# ------------------------------------------------------------------------------ YawRateValue yaw_rate_value YawRateConfidence yaw_rate_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg index 397121d65..a3a9eaab3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg @@ -25,7 +25,19 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED YawRateConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# YawRateConfidence ::= ENUMERATED { +# degSec-000-01 (0), +# degSec-000-05 (1), +# degSec-000-10 (2), +# degSec-001-00 (3), +# degSec-005-00 (4), +# degSec-010-00 (5), +# degSec-100-00 (6), +# outOfRange (7), +# unavailable (8) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 DEG_SEC_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg index d3ebfedd5..3cf3b6b18 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER YawRateValue +# --- ASN.1 Definition --------------------------------------------------------- +# YawRateValue ::= INTEGER {straight(0), degSec-000-01ToRight(-1), degSec-000-01ToLeft(1), unavailable(32767)} (-32766..32767) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -32766 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg index 2c96c29bd..d8f12b08b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AccelerationConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# AccelerationConfidence ::= INTEGER {pointOneMeterPerSecSquared(1), outOfRange(101), unavailable(102)} (0 .. 102) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg index 59891bb3a..b9a2fcc83 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg @@ -25,7 +25,17 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING AccelerationControl +# --- ASN.1 Definition --------------------------------------------------------- +# AccelerationControl ::= BIT STRING { +# brakePedalEngaged (0), +# gasPedalEngaged (1), +# emergencyBrakeEngaged (2), +# collisionWarningEngaged (3), +# accEngaged (4), +# cruiseControlEngaged (5), +# speedLimiterEngaged (6) +# } (SIZE(7)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg index 2e85a1965..62efd6e30 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AccidentSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AccidentSubCauseCode ::= INTEGER {unavailable(0), multiVehicleAccident(1), heavyAccident(2), accidentInvolvingLorry(3), accidentInvolvingBus(4), accidentInvolvingHazardousMaterials(5), accidentOnOppositeLane(6), unsecuredAccident(7), assistanceRequested(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg index 14f623b35..8ebd1d181 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ActionID +# --- ASN.1 Definition --------------------------------------------------------- +# ActionID ::= SEQUENCE { +# originatingStationID StationID, +# sequenceNumber SequenceNumber +# } +# ------------------------------------------------------------------------------ StationID originating_station_id SequenceNumber sequence_number diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 4d5baa2ef..5e2955099 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionAdhesionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-AdhesionSubCauseCode ::= INTEGER {unavailable(0), heavyFrostOnRoad(1), fuelOnRoad(2), mudOnRoad(3), snowOnRoad(4), iceOnRoad(5), blackIceOnRoad(6), oilOnRoad(7), looseChippings(8), instantBlackIce(9), roadsSalted(10)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index a45f41e0f..40958b76c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-ExtremeWeatherConditionSubCauseCode ::= INTEGER {unavailable(0), strongWinds(1), damagingHail(2), hurricane(3), thunderstorm(4), tornado(5), blizzard(6)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index afe120d54..b087e8491 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionPrecipitationSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-PrecipitationSubCauseCode ::= INTEGER {unavailable(0), heavyRain(1), heavySnowfall(2), softHail(3)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 84b13bbde..279aa3ad6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AdverseWeatherConditionVisibilitySubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# AdverseWeatherCondition-VisibilitySubCauseCode ::= INTEGER {unavailable(0), fog(1), smoke(2), heavySnowfall(3), heavyRain(4), heavyHail(5), lowSunGlare(6), sandstorms(7), swarmsOfInsects(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg index 85bd572f4..f9f8d8bfb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg @@ -25,7 +25,17 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE AlacarteContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# AlacarteContainer ::= SEQUENCE { +# lanePosition LanePosition OPTIONAL, +# impactReduction ImpactReductionContainer OPTIONAL, +# externalTemperature Temperature OPTIONAL, +# roadWorks RoadWorksContainerExtended OPTIONAL, +# positioningSolution PositioningSolutionType OPTIONAL, +# stationaryVehicle StationaryVehicleContainer OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ LanePosition lane_position bool lane_position_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg index 18a7e620d..d33ad18f6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Altitude +# --- ASN.1 Definition --------------------------------------------------------- +# Altitude ::= SEQUENCE { +# altitudeValue AltitudeValue, +# altitudeConfidence AltitudeConfidence +# } +# ------------------------------------------------------------------------------ AltitudeValue altitude_value AltitudeConfidence altitude_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg index 7c3a95c22..0d49d5dfd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg @@ -25,7 +25,26 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED AltitudeConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# AltitudeConfidence ::= ENUMERATED { +# alt-000-01 (0), +# alt-000-02 (1), +# alt-000-05 (2), +# alt-000-10 (3), +# alt-000-20 (4), +# alt-000-50 (5), +# alt-001-00 (6), +# alt-002-00 (7), +# alt-005-00 (8), +# alt-010-00 (9), +# alt-020-00 (10), +# alt-050-00 (11), +# alt-100-00 (12), +# alt-200-00 (13), +# outOfRange (14), +# unavailable (15) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 ALT_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg index 4dbc604e6..ced7117ff 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER AltitudeValue +# --- ASN.1 Definition --------------------------------------------------------- +# AltitudeValue ::= INTEGER {referenceEllipsoidSurface(0), oneCentimeter(1), unavailable(800001)} (-100000..800001) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -100000 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg index 46fa8aed4..9260033c6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CauseCode .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CauseCode ::= SEQUENCE { +# causeCode CauseCodeType, +# subCauseCode SubCauseCodeType, +# ... +# } +# ------------------------------------------------------------------------------ CauseCodeType cause_code SubCauseCodeType sub_cause_code diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg index 61c553d96..c3034f85f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg @@ -25,7 +25,37 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER CauseCodeType +# --- ASN.1 Definition --------------------------------------------------------- +# CauseCodeType ::= INTEGER { +# reserved (0), +# trafficCondition (1), +# accident (2), +# roadworks (3), +# impassability (5), +# adverseWeatherCondition-Adhesion (6), +# aquaplannning (7), +# hazardousLocation-SurfaceCondition (9), +# hazardousLocation-ObstacleOnTheRoad (10), +# hazardousLocation-AnimalOnTheRoad (11), +# humanPresenceOnTheRoad (12), +# wrongWayDriving (14), +# rescueAndRecoveryWorkInProgress (15), +# adverseWeatherCondition-ExtremeWeatherCondition (17), +# adverseWeatherCondition-Visibility (18), +# adverseWeatherCondition-Precipitation (19), +# slowVehicle (26), +# dangerousEndOfQueue (27), +# vehicleBreakdown (91), +# postCrash (92), +# humanProblem (93), +# stationaryVehicle (94), +# emergencyVehicleApproaching (95), +# hazardousLocation-DangerousCurve (96), +# collisionRisk (97), +# signalViolation (98), +# dangerousSituation (99) +# } (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg index 96a17295f..cf12d0483 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE CenDsrcTollingZone .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CenDsrcTollingZone ::= SEQUENCE { +# protectedZoneLatitude Latitude, +# protectedZoneLongitude Longitude, +# cenDsrcTollingZoneID CenDsrcTollingZoneID OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ Latitude protected_zone_latitude Longitude protected_zone_longitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg index 6fc8d1f81..dd12f6a75 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## TYPE-ALIAS CenDsrcTollingZoneID +# --- ASN.1 Definition --------------------------------------------------------- +# CenDsrcTollingZoneID ::= ProtectedZoneID +# ------------------------------------------------------------------------------ ProtectedZoneID value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg index 55b9c5f22..b4ff53fbf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ClosedLanes .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ClosedLanes ::= SEQUENCE { +# innerhardShoulderStatus HardShoulderStatus OPTIONAL, +# outerhardShoulderStatus HardShoulderStatus OPTIONAL, +# drivingLaneStatus DrivingLaneStatus OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ HardShoulderStatus innerhard_shoulder_status bool innerhard_shoulder_status_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg index a1439f329..088c70f41 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER CollisionRiskSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# CollisionRiskSubCauseCode ::= INTEGER {unavailable(0), longitudinalCollisionRisk(1), crossingCollisionRisk(2), lateralCollisionRisk(3), vulnerableRoadUser(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg index 6aead5fdf..c9f50f1b2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Curvature +# --- ASN.1 Definition --------------------------------------------------------- +# Curvature ::= SEQUENCE { +# curvatureValue CurvatureValue, +# curvatureConfidence CurvatureConfidence +# } +# ------------------------------------------------------------------------------ CurvatureValue curvature_value CurvatureConfidence curvature_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg index b9e8e49d3..c7166a4dd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED CurvatureCalculationMode .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# CurvatureCalculationMode ::= ENUMERATED {yawRateUsed(0), yawRateNotUsed(1), unavailable(2), ...} +# ------------------------------------------------------------------------------ uint8 value uint8 YAW_RATE_USED = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg index b36c4ea4d..014ac9603 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg @@ -25,7 +25,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED CurvatureConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# CurvatureConfidence ::= ENUMERATED { +# onePerMeter-0-00002 (0), +# onePerMeter-0-0001 (1), +# onePerMeter-0-0005 (2), +# onePerMeter-0-002 (3), +# onePerMeter-0-01 (4), +# onePerMeter-0-1 (5), +# outOfRange (6), +# unavailable (7) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 ONE_PER_METER_0_00002 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg index 1607dc28d..ebb64831c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER CurvatureValue +# --- ASN.1 Definition --------------------------------------------------------- +# CurvatureValue ::= INTEGER {straight(0), unavailable(1023)} (-1023..1023) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -1023 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg index 85f1c120f..78254d73e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DENM +# --- ASN.1 Definition --------------------------------------------------------- +# DENM ::= SEQUENCE { +# header ItsPduHeader, +# denm DecentralizedEnvironmentalNotificationMessage +# } +# ------------------------------------------------------------------------------ ItsPduHeader header DecentralizedEnvironmentalNotificationMessage denm diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index 9484263ff..5625ad6c4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DangerousEndOfQueueSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousEndOfQueueSubCauseCode ::= INTEGER {unavailable(0), suddenEndOfQueue(1), queueOverHill(2), queueAroundBend(3), queueInTunnel(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg index 9213942db..f49e5e2bc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg @@ -25,7 +25,30 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED DangerousGoodsBasic +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousGoodsBasic::= ENUMERATED { +# explosives1(0), +# explosives2(1), +# explosives3(2), +# explosives4(3), +# explosives5(4), +# explosives6(5), +# flammableGases(6), +# nonFlammableGases(7), +# toxicGases(8), +# flammableLiquids(9), +# flammableSolids(10), +# substancesLiableToSpontaneousCombustion(11), +# substancesEmittingFlammableGasesUponContactWithWater(12), +# oxidizingSubstances(13), +# organicPeroxides(14), +# toxicSubstances(15), +# infectiousSubstances(16), +# radioactiveMaterial(17), +# corrosiveSubstances(18), +# miscellaneousDangerousSubstances(19) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 EXPLOSIVES_1 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg index 91afc5574..38e4e4c18 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg @@ -25,7 +25,19 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DangerousGoodsExtended .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousGoodsExtended ::= SEQUENCE { +# dangerousGoodsType DangerousGoodsBasic, +# unNumber INTEGER (0..9999), +# elevatedTemperature BOOLEAN, +# tunnelsRestricted BOOLEAN, +# limitedQuantity BOOLEAN, +# emergencyActionCode IA5String (SIZE (1..24)) OPTIONAL, +# phoneNumber PhoneNumber OPTIONAL, +# companyName UTF8String (SIZE (1..24)) OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ DangerousGoodsBasic dangerous_goods_type uint16 un_number diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg index 52ec15222..ff8f082b4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DangerousSituationSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# DangerousSituationSubCauseCode ::= INTEGER {unavailable(0), emergencyElectronicBrakeEngaged(1), preCrashSystemEngaged(2), espEngaged(3), absEngaged(4), aebEngaged(5), brakeWarningEngaged(6), collisionRiskWarningEngaged(7)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg index 885a7bf1b..0095eceeb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DecentralizedEnvironmentalNotificationMessage +# --- ASN.1 Definition --------------------------------------------------------- +# DecentralizedEnvironmentalNotificationMessage ::= SEQUENCE { +# management ManagementContainer, +# situation SituationContainer OPTIONAL, +# location LocationContainer OPTIONAL, +# alacarte AlacarteContainer OPTIONAL +# } +# ------------------------------------------------------------------------------ ManagementContainer management SituationContainer situation diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg index 19e2b4ffd..42e3c7d66 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DeltaAltitude +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaAltitude ::= INTEGER {oneCentimeterUp (1), oneCentimeterDown (-1), unavailable(12800)} (-12700..12800) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -12700 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg index b9977f0d4..8316b7c49 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DeltaLatitude +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaLatitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10) , unavailable(131072)} (-131071..131072) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -131071 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg index 73d04ec5a..001a1fa12 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER DeltaLongitude +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaLongitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(131072)} (-131071..131072) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -131071 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg index 7ae8cd306..fd91f916d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE DeltaReferencePosition +# --- ASN.1 Definition --------------------------------------------------------- +# DeltaReferencePosition ::= SEQUENCE { +# deltaLatitude DeltaLatitude, +# deltaLongitude DeltaLongitude, +# deltaAltitude DeltaAltitude +# } +# ------------------------------------------------------------------------------ DeltaLatitude delta_latitude DeltaLongitude delta_longitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg index d67682243..9b9b8097a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF DigitalMap +# --- ASN.1 Definition --------------------------------------------------------- +# DigitalMap ::= SEQUENCE (SIZE(1..256)) OF ReferencePosition +# ------------------------------------------------------------------------------ ReferencePosition[] array uint16 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg index 2d1c95e2a..75d1f4936 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED DriveDirection +# --- ASN.1 Definition --------------------------------------------------------- +# DriveDirection ::= ENUMERATED {forward (0), backward (1), unavailable (2)} +# ------------------------------------------------------------------------------ uint8 value uint8 FORWARD = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg index 43ea6ca1c..f55056461 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING DrivingLaneStatus +# --- ASN.1 Definition --------------------------------------------------------- +# DrivingLaneStatus ::= BIT STRING (SIZE (1..13)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg index b52eb16db..6459d3da9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BOOLEAN EmbarkationStatus +# --- ASN.1 Definition --------------------------------------------------------- +# EmbarkationStatus ::= BOOLEAN +# ------------------------------------------------------------------------------ bool value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg index d9a335ed9..fec313c25 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING EmergencyPriority +# --- ASN.1 Definition --------------------------------------------------------- +# EmergencyPriority ::= BIT STRING {requestForRightOfWay(0), requestForFreeCrossingAtATrafficLight(1)} (SIZE(2)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 33eb4fbbd..119607ee3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER EmergencyVehicleApproachingSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# EmergencyVehicleApproachingSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicleApproaching(1), prioritizedVehicleApproaching(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg index ffdd50c96..c8d184879 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING EnergyStorageType +# --- ASN.1 Definition --------------------------------------------------------- +# EnergyStorageType ::= BIT STRING {hydrogenStorage(0), electricEnergyStorage(1), liquidPropaneGas(2), compressedNaturalGas(3), diesel(4), gasoline(5), ammonia(6)} (SIZE(7)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg index 6cc1045b6..7171933f8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF EventHistory +# --- ASN.1 Definition --------------------------------------------------------- +# EventHistory::= SEQUENCE (SIZE(1..23)) OF EventPoint +# ------------------------------------------------------------------------------ EventPoint[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg index c0fcc5bae..4514b8d6b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE EventPoint +# --- ASN.1 Definition --------------------------------------------------------- +# EventPoint ::= SEQUENCE { +# eventPosition DeltaReferencePosition, +# eventDeltaTime PathDeltaTime OPTIONAL, +# informationQuality InformationQuality +# } +# ------------------------------------------------------------------------------ DeltaReferencePosition event_position PathDeltaTime event_delta_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg index 77a240fb1..bf1abac96 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg @@ -25,7 +25,18 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING ExteriorLights +# --- ASN.1 Definition --------------------------------------------------------- +# ExteriorLights ::= BIT STRING { +# lowBeamHeadlightsOn (0), +# highBeamHeadlightsOn (1), +# leftTurnSignalOn (2), +# rightTurnSignalOn (3), +# daytimeRunningLightsOn (4), +# reverseLightOn (5), +# fogLightOn (6), +# parkingLightsOn (7) +# } (SIZE(8)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg index e19c27a02..b829dcda2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED HardShoulderStatus +# --- ASN.1 Definition --------------------------------------------------------- +# HardShoulderStatus ::= ENUMERATED {availableForStopping(0), closed(1), availableForDriving(2)} +# ------------------------------------------------------------------------------ uint8 value uint8 AVAILABLE_FOR_STOPPING = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 762fd771a..4766634a3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-AnimalOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), wildAnimals(1), herdOfAnimals(2), smallAnimals(3), largeAnimals(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index ff1002498..02551d9e1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationDangerousCurveSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-DangerousCurveSubCauseCode ::= INTEGER {unavailable(0), dangerousLeftTurnCurve(1), dangerousRightTurnCurve(2), multipleCurvesStartingWithUnknownTurningDirection(3), multipleCurvesStartingWithLeftTurn(4), multipleCurvesStartingWithRightTurn(5)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index aff6952f3..d0eee3f2e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-ObstacleOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), shedLoad(1), partsOfVehicles(2), partsOfTyres(3), bigObjects(4), fallenTrees(5), hubCaps(6), waitingVehicles(7)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 5b1536bee..4e147ca9d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HazardousLocationSurfaceConditionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HazardousLocation-SurfaceConditionSubCauseCode ::= INTEGER {unavailable(0), rockfalls(1), earthquakeDamage(2), sewerCollapse(3), subsidence(4), snowDrifts(5), stormDamage(6), burstPipe(7), volcanoEruption(8), fallingIce(9)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg index 961b9a6c6..79915064f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Heading +# --- ASN.1 Definition --------------------------------------------------------- +# Heading ::= SEQUENCE { +# headingValue HeadingValue, +# headingConfidence HeadingConfidence +# } +# ------------------------------------------------------------------------------ HeadingValue heading_value HeadingConfidence heading_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg index 18b074792..e449a7d2a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HeadingConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# HeadingConfidence ::= INTEGER {equalOrWithinZeroPointOneDegree (1), equalOrWithinOneDegree (10), outOfRange(126), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg index bf95b1054..01ecf4177 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HeadingValue +# --- ASN.1 Definition --------------------------------------------------------- +# HeadingValue ::= INTEGER {wgs84North(0), wgs84East(900), wgs84South(1800), wgs84West(2700), unavailable(3601)} (0..3601) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg index 6456533de..a57e51b95 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HeightLonCarr +# --- ASN.1 Definition --------------------------------------------------------- +# HeightLonCarr ::= INTEGER {oneCentimeter(1), unavailable(100)} (1..100) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index 879b64b81..a59935c0a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HumanPresenceOnTheRoadSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HumanPresenceOnTheRoadSubCauseCode ::= INTEGER {unavailable(0), childrenOnRoadway(1), cyclistOnRoadway(2), motorcyclistOnRoadway(3)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg index 3a91e85c7..50d2c72b9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER HumanProblemSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# HumanProblemSubCauseCode ::= INTEGER {unavailable(0), glycemiaProblem(1), heartProblem(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg index f0d813021..bc60e4ae8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg @@ -25,7 +25,22 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ImpactReductionContainer +# --- ASN.1 Definition --------------------------------------------------------- +# ImpactReductionContainer ::= SEQUENCE { +# heightLonCarrLeft HeightLonCarr, +# heightLonCarrRight HeightLonCarr, +# posLonCarrLeft PosLonCarr, +# posLonCarrRight PosLonCarr, +# positionOfPillars PositionOfPillars, +# posCentMass PosCentMass, +# wheelBaseVehicle WheelBaseVehicle, +# turningRadius TurningRadius, +# posFrontAx PosFrontAx, +# positionOfOccupants PositionOfOccupants, +# vehicleMass VehicleMass, +# requestResponseIndication RequestResponseIndication +# } +# ------------------------------------------------------------------------------ HeightLonCarr height_lon_carr_left HeightLonCarr height_lon_carr_right diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg index bd50329f8..aaa05b44b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER InformationQuality +# --- ASN.1 Definition --------------------------------------------------------- +# InformationQuality ::= INTEGER {unavailable(0), lowest(1), highest(7)} (0..7) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg index 4b62379b8..cba1ae5eb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF ItineraryPath +# --- ASN.1 Definition --------------------------------------------------------- +# ItineraryPath ::= SEQUENCE SIZE(1..40) OF ReferencePosition +# ------------------------------------------------------------------------------ ReferencePosition[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg index 16d132739..f7a6a34b0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg @@ -25,7 +25,11 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ItsPduHeader +# --- ASN.1 Definition --------------------------------------------------------- +# ItsPduHeader ::= SEQUENCE { +# protocolVersion INTEGER (0..255), +# messageID INTEGER{ denm(1), cam(2), poi(3), spatem(4), mapem(5), ivim(6), ev-rsr(7), tistpgtransaction(8), srem(9), ssem(10), evcsn(11), saem(12), rtcmem(13) } (0..255), -- Mantis #7209, #7005 +# ------------------------------------------------------------------------------ uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 uint8 PROTOCOL_VERSION_MAX = 255 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg index 14b6304e1..cf2c4184e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg @@ -25,7 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER LanePosition +# --- ASN.1 Definition --------------------------------------------------------- +# LanePosition::= INTEGER {offTheRoad(-1), hardShoulder(0), +# outermostDrivingLane(1), secondLaneFromOutside(2)} (-1..14) +# ------------------------------------------------------------------------------ int8 value int8 MIN = -1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg index 8a7b7678d..3e2f5d914 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE LateralAcceleration +# --- ASN.1 Definition --------------------------------------------------------- +# LateralAcceleration ::= SEQUENCE { +# lateralAccelerationValue LateralAccelerationValue, +# lateralAccelerationConfidence AccelerationConfidence +# } +# ------------------------------------------------------------------------------ LateralAccelerationValue lateral_acceleration_value AccelerationConfidence lateral_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg index ff380dc60..c0c95cdf3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER LateralAccelerationValue +# --- ASN.1 Definition --------------------------------------------------------- +# LateralAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredToRight(-1), pointOneMeterPerSecSquaredToLeft(1), unavailable(161)} (-160 .. 161) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -160 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg index c7cd97580..d6790b6a7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER Latitude +# --- ASN.1 Definition --------------------------------------------------------- +# Latitude ::= INTEGER {oneMicrodegreeNorth (10), oneMicrodegreeSouth (-10), unavailable(900000001)} (-900000000..900000001) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -900000000 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg index b58c05ebb..af41f3d23 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING LightBarSirenInUse +# --- ASN.1 Definition --------------------------------------------------------- +# LightBarSirenInUse ::= BIT STRING { +# lightBarActivated (0), +# sirenActivated (1) +# } (SIZE(2)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg index 31fe73a21..0f3715012 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg @@ -25,7 +25,15 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE LocationContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# LocationContainer ::= SEQUENCE { +# eventSpeed Speed OPTIONAL, +# eventPositionHeading Heading OPTIONAL, +# traces Traces, +# roadType RoadType OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ Speed event_speed bool event_speed_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg index 341e21778..0d881d795 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER Longitude +# --- ASN.1 Definition --------------------------------------------------------- +# Longitude ::= INTEGER {oneMicrodegreeEast (10), oneMicrodegreeWest (-10), unavailable(1800000001)} (-1800000000..1800000001) +# ------------------------------------------------------------------------------ int32 value int32 MIN = -1800000000 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg index 4880b8e99..f8ce9be22 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE LongitudinalAcceleration +# --- ASN.1 Definition --------------------------------------------------------- +# LongitudinalAcceleration ::= SEQUENCE { +# longitudinalAccelerationValue LongitudinalAccelerationValue, +# longitudinalAccelerationConfidence AccelerationConfidence +# } +# ------------------------------------------------------------------------------ LongitudinalAccelerationValue longitudinal_acceleration_value AccelerationConfidence longitudinal_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg index e5e387119..5490b1049 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER LongitudinalAccelerationValue +# --- ASN.1 Definition --------------------------------------------------------- +# LongitudinalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredForward(1), pointOneMeterPerSecSquaredBackward(-1), unavailable(161)} (-160 .. 161) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -160 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg index 13f77c76d..618922061 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg @@ -25,7 +25,21 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ManagementContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ManagementContainer ::= SEQUENCE { +# actionID ActionID, +# detectionTime TimestampIts, +# referenceTime TimestampIts, +# termination Termination OPTIONAL, +# eventPosition ReferencePosition, +# relevanceDistance RelevanceDistance OPTIONAL, +# relevanceTrafficDirection RelevanceTrafficDirection OPTIONAL, +# validityDuration ValidityDuration DEFAULT defaultValidity, +# transmissionInterval TransmissionInterval OPTIONAL, +# stationType StationType, +# ... +# } +# ------------------------------------------------------------------------------ ActionID action_id TimestampIts detection_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg index 09d9ceb5c..29866b9b5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER NumberOfOccupants +# --- ASN.1 Definition --------------------------------------------------------- +# NumberOfOccupants ::= INTEGER {oneOccupant (1), unavailable(127)} (0 .. 127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg index ea4ca5882..ed47dd83f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## Utf8String OpeningDaysHours +# --- ASN.1 Definition --------------------------------------------------------- +# OpeningDaysHours ::= UTF8String +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg index f95b5adbc..eb535a512 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PathDeltaTime +# --- ASN.1 Definition --------------------------------------------------------- +# PathDeltaTime ::= INTEGER {tenMilliSecondsInPast(1)} (1..65535, ...) +# ------------------------------------------------------------------------------ int64 value int64 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg index 9a72d15bc..a01230954 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF PathHistory +# --- ASN.1 Definition --------------------------------------------------------- +# PathHistory::= SEQUENCE (SIZE(0..40)) OF PathPoint +# ------------------------------------------------------------------------------ PathPoint[] array uint8 MIN_SIZE = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg index 87ce1b575..beb29a984 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PathPoint +# --- ASN.1 Definition --------------------------------------------------------- +# PathPoint ::= SEQUENCE { +# pathPosition DeltaReferencePosition, +# pathDeltaTime PathDeltaTime OPTIONAL +# } +# ------------------------------------------------------------------------------ DeltaReferencePosition path_position PathDeltaTime path_delta_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg index 5e2f9a67f..5e647048f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PerformanceClass +# --- ASN.1 Definition --------------------------------------------------------- +# PerformanceClass ::= INTEGER {unavailable(0), performanceClassA(1), performanceClassB(2)} (0..7) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg index 87c284302..4406676ab 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## NumericString PhoneNumber +# --- ASN.1 Definition --------------------------------------------------------- +# PhoneNumber ::= NumericString (SIZE(1..16)) +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg index 18bb04a98..eb542bcf9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosCentMass +# --- ASN.1 Definition --------------------------------------------------------- +# PosCentMass ::= INTEGER {tenCentimeters(1), unavailable(63)} (1..63) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg index aeb665ecc..69e6be2a2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PosConfidenceEllipse +# --- ASN.1 Definition --------------------------------------------------------- +# PosConfidenceEllipse ::= SEQUENCE { +# semiMajorConfidence SemiAxisLength, +# semiMinorConfidence SemiAxisLength, +# semiMajorOrientation HeadingValue +# } +# ------------------------------------------------------------------------------ SemiAxisLength semi_major_confidence SemiAxisLength semi_minor_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg index 8cfd73ba9..dec614584 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosFrontAx +# --- ASN.1 Definition --------------------------------------------------------- +# PosFrontAx ::= INTEGER {tenCentimeters(1), unavailable(20)} (1..20) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg index 5efdc3d90..56a23793c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosLonCarr +# --- ASN.1 Definition --------------------------------------------------------- +# PosLonCarr ::= INTEGER {oneCentimeter(1), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg index 6294ffc82..f000268e6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PosPillar +# --- ASN.1 Definition --------------------------------------------------------- +# PosPillar ::= INTEGER {tenCentimeters(1), unavailable(30)} (1..30) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg index 72347aba9..bab7e4e92 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg @@ -25,7 +25,29 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING PositionOfOccupants +# --- ASN.1 Definition --------------------------------------------------------- +# PositionOfOccupants ::= BIT STRING { +# row1LeftOccupied (0), +# row1RightOccupied (1), +# row1MidOccupied (2), +# row1NotDetectable (3), +# row1NotPresent (4), +# row2LeftOccupied (5), +# row2RightOccupied (6), +# row2MidOccupied (7), +# row2NotDetectable (8), +# row2NotPresent (9), +# row3LeftOccupied (10), +# row3RightOccupied (11), +# row3MidOccupied (12), +# row3NotDetectable (13), +# row3NotPresent (14), +# row4LeftOccupied (15), +# row4RightOccupied (16), +# row4MidOccupied (17), +# row4NotDetectable (18), +# row4NotPresent (19)} (SIZE(20)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg index 824502493..7db286c34 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF PositionOfPillars +# --- ASN.1 Definition --------------------------------------------------------- +# PositionOfPillars ::= SEQUENCE (SIZE(1..3, ...)) OF PosPillar +# ------------------------------------------------------------------------------ PosPillar[] array int64 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg index aad52eeb7..1032ae4b1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED PositioningSolutionType .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# PositioningSolutionType ::= ENUMERATED {noPositioningSolution(0), sGNSS(1), dGNSS(2), sGNSSplusDR(3), dGNSSplusDR(4), dR(5), ...} +# ------------------------------------------------------------------------------ uint8 value uint8 NO_POSITIONING_SOLUTION = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg index 5dabb7149..85a35798a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PostCrashSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# PostCrashSubCauseCode ::= INTEGER {unavailable(0), accidentWithoutECallTriggered (1), accidentWithECallManuallyTriggered (2), accidentWithECallAutomaticallyTriggered (3), accidentWithECallTriggeredWithoutAccessToCellularNetwork(4)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg index d8ac4b043..d1335c7cc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg @@ -25,7 +25,17 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ProtectedCommunicationZone .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedCommunicationZone ::= SEQUENCE { +# protectedZoneType ProtectedZoneType, +# expiryTime TimestampIts OPTIONAL, +# protectedZoneLatitude Latitude, +# protectedZoneLongitude Longitude, +# protectedZoneRadius ProtectedZoneRadius OPTIONAL, +# protectedZoneID ProtectedZoneID OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ ProtectedZoneType protected_zone_type TimestampIts expiry_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg index 43650b6c2..2d5f9f9a4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF ProtectedCommunicationZonesRSU +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedCommunicationZonesRSU ::= SEQUENCE (SIZE(1..16)) OF ProtectedCommunicationZone +# ------------------------------------------------------------------------------ ProtectedCommunicationZone[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg index ae4c41709..bb4f93c32 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER ProtectedZoneID +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedZoneID ::= INTEGER (0.. 134217727) +# ------------------------------------------------------------------------------ uint32 value uint32 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg index adf686ea1..97a3ead2e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER ProtectedZoneRadius +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedZoneRadius ::= INTEGER {oneMeter(1)} (1..255,...) +# ------------------------------------------------------------------------------ int64 value int64 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg index 812c608d7..9ba419cec 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED ProtectedZoneType .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# ProtectedZoneType::= ENUMERATED { permanentCenDsrcTolling (0), ..., temporaryCenDsrcTolling (1) } +# ------------------------------------------------------------------------------ uint8 value uint8 PERMANENT_CEN_DSRC_TOLLING = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg index f6fdbe3ea..32c276aa5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE PtActivation +# --- ASN.1 Definition --------------------------------------------------------- +# PtActivation ::= SEQUENCE { +# ptActivationType PtActivationType, +# ptActivationData PtActivationData +# } +# ------------------------------------------------------------------------------ PtActivationType pt_activation_type PtActivationData pt_activation_data diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg index 9e0108cdf..f0da8da3a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg @@ -1,3 +1,5 @@ -## OCTET-STRING PtActivationData +# --- ASN.1 Definition --------------------------------------------------------- +# PtActivationData ::= OCTET STRING (SIZE(1..20)) +# ------------------------------------------------------------------------------ uint8[] value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg index 16c038fa4..1d3a14412 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER PtActivationType +# --- ASN.1 Definition --------------------------------------------------------- +# PtActivationType ::= INTEGER {undefinedCodingType(0), r09-16CodingType(1), vdv-50149CodingType(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg index 7764cad05..ea13c3cf8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF ReferenceDenms +# --- ASN.1 Definition --------------------------------------------------------- +# ReferenceDenms ::= SEQUENCE (SIZE(1..8, ...)) OF ActionID +# ------------------------------------------------------------------------------ ActionID[] array int64 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg index 07a4e8e6d..738b78443 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg @@ -25,7 +25,14 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE ReferencePosition +# --- ASN.1 Definition --------------------------------------------------------- +# ReferencePosition ::= SEQUENCE { +# latitude Latitude, +# longitude Longitude, +# positionConfidenceEllipse PosConfidenceEllipse , +# altitude Altitude +# } +# ------------------------------------------------------------------------------ Latitude latitude Longitude longitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg index 443ca5e6f..4bdc9a00c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RelevanceDistance +# --- ASN.1 Definition --------------------------------------------------------- +# RelevanceDistance ::= ENUMERATED {lessThan50m(0), lessThan100m(1), lessThan200m(2), lessThan500m(3), lessThan1000m(4), lessThan5km(5), lessThan10km(6), over10km(7)} +# ------------------------------------------------------------------------------ uint8 value uint8 LESS_THAN_50M = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg index 867fa1853..23849c372 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RelevanceTrafficDirection +# --- ASN.1 Definition --------------------------------------------------------- +# RelevanceTrafficDirection ::= ENUMERATED {allTrafficDirections(0), upstreamTraffic(1), downstreamTraffic(2), oppositeTraffic(3)} +# ------------------------------------------------------------------------------ uint8 value uint8 ALL_TRAFFIC_DIRECTIONS = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg index 856dfe2fb..7a88dc8db 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RequestResponseIndication +# --- ASN.1 Definition --------------------------------------------------------- +# RequestResponseIndication ::= ENUMERATED {request(0), response(1)} +# ------------------------------------------------------------------------------ uint8 value uint8 REQUEST = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index aed759dcc..427e20f40 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER RescueAndRecoveryWorkInProgressSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# RescueAndRecoveryWorkInProgressSubCauseCode ::= INTEGER {unavailable(0), emergencyVehicles(1), rescueHelicopterLanding(2), policeActivityOngoing(3), medicalEmergencyOngoing(4), childAbductionInProgress(5)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg index ebdb78e61..f9c80d5be 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF RestrictedTypes +# --- ASN.1 Definition --------------------------------------------------------- +# RestrictedTypes ::= SEQUENCE (SIZE(1..3, ...)) OF StationType +# ------------------------------------------------------------------------------ StationType[] array int64 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg index 7ab57d5c2..7280b7c6b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED RoadType +# --- ASN.1 Definition --------------------------------------------------------- +# RoadType ::= ENUMERATED { +# urban-NoStructuralSeparationToOppositeLanes(0), +# urban-WithStructuralSeparationToOppositeLanes(1), +# nonUrban-NoStructuralSeparationToOppositeLanes(2), +# nonUrban-WithStructuralSeparationToOppositeLanes(3)} +# ------------------------------------------------------------------------------ uint8 value uint8 URBAN_NO_STRUCTURAL_SEPARATION_TO_OPPOSITE_LANES = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg index 177df9da4..5e18e5977 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg @@ -25,7 +25,19 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE RoadWorksContainerExtended +# --- ASN.1 Definition --------------------------------------------------------- +# RoadWorksContainerExtended ::= SEQUENCE { +# lightBarSirenInUse LightBarSirenInUse OPTIONAL, +# closedLanes ClosedLanes OPTIONAL, +# restriction RestrictedTypes OPTIONAL, +# speedLimit SpeedLimit OPTIONAL, +# incidentIndication CauseCode OPTIONAL, +# recommendedPath ItineraryPath OPTIONAL, +# startingPointSpeedLimit DeltaReferencePosition OPTIONAL, +# trafficFlowRule TrafficRule OPTIONAL, +# referenceDenms ReferenceDenms OPTIONAL +# } +# ------------------------------------------------------------------------------ LightBarSirenInUse light_bar_siren_in_use bool light_bar_siren_in_use_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg index 1b12c35e4..017a34d21 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER RoadworksSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# RoadworksSubCauseCode ::= INTEGER {unavailable(0), majorRoadworks(1), roadMarkingWork(2), slowMovingRoadMaintenance(3), shortTermStationaryRoadworks(4), streetCleaning(5), winterService(6)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg index c4c1c38ec..fbd569ec1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SemiAxisLength +# --- ASN.1 Definition --------------------------------------------------------- +# SemiAxisLength ::= INTEGER{oneCentimeter(1), outOfRange(4094), unavailable(4095)} (0..4095) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg index 27a36a32c..8fd8be07e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SequenceNumber +# --- ASN.1 Definition --------------------------------------------------------- +# SequenceNumber ::= INTEGER (0..65535) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg index bb8a3c386..6286201a3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SignalViolationSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# SignalViolationSubCauseCode ::= INTEGER {unavailable(0), stopSignViolation(1), trafficLightViolation(2), turningRegulationViolation(3)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg index 3b464a32c..583baddcb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg @@ -25,7 +25,15 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE SituationContainer .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# SituationContainer ::= SEQUENCE { +# informationQuality InformationQuality, +# eventType CauseCode, +# linkedCause CauseCode OPTIONAL, +# eventHistory EventHistory OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ InformationQuality information_quality CauseCode event_type diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg index faf4093de..ffc371dec 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SlowVehicleSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# SlowVehicleSubCauseCode ::= INTEGER {unavailable(0), maintenanceVehicle(1), vehiclesSlowingToLookAtAccident(2), abnormalLoad(3), abnormalWideLoad(4), convoy(5), snowplough(6), deicing(7), saltingVehicles(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg index 8444a35ea..7bfb3f184 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## BIT-STRING SpecialTransportType +# --- ASN.1 Definition --------------------------------------------------------- +# SpecialTransportType ::= BIT STRING {heavyLoad(0), excessWidth(1), excessLength(2), excessHeight(3)} (SIZE(4)) +# ------------------------------------------------------------------------------ uint8[] value uint8 bits_unused diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg index f603b1dcc..e6a686f59 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE Speed +# --- ASN.1 Definition --------------------------------------------------------- +# Speed ::= SEQUENCE { +# speedValue SpeedValue, +# speedConfidence SpeedConfidence +# } +# ------------------------------------------------------------------------------ SpeedValue speed_value SpeedConfidence speed_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg index 930449281..3001fa3f3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SpeedConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# SpeedConfidence ::= INTEGER {equalOrWithinOneCentimeterPerSec(1), equalOrWithinOneMeterPerSec(100), outOfRange(126), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg index 3fd12e847..5eb6c64c4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SpeedLimit +# --- ASN.1 Definition --------------------------------------------------------- +# SpeedLimit ::= INTEGER {oneKmPerHour(1)} (1..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg index 9617fb469..978abe6e5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SpeedValue +# --- ASN.1 Definition --------------------------------------------------------- +# SpeedValue ::= INTEGER {standstill(0), oneCentimeterPerSec(1), unavailable(16383)} (0..16383) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg index 9e5dc24dd..6cf2e47dc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER StationID +# --- ASN.1 Definition --------------------------------------------------------- +# StationID ::= INTEGER(0..4294967295) +# ------------------------------------------------------------------------------ uint32 value uint32 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg index 82a3cc1ea..d84cf4192 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg @@ -25,7 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER StationType +# --- ASN.1 Definition --------------------------------------------------------- +# StationType ::= INTEGER {unknown(0), pedestrian(1), cyclist(2), moped(3), motorcycle(4), passengerCar(5), bus(6), +# lightTruck(7), heavyTruck(8), trailer(9), specialVehicles(10), tram(11), roadSideUnit(15)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg index a35450fd1..6cd027626 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED StationarySince +# --- ASN.1 Definition --------------------------------------------------------- +# StationarySince ::= ENUMERATED {lessThan1Minute(0), lessThan2Minutes(1), lessThan15Minutes(2), equalOrGreater15Minutes(3)} +# ------------------------------------------------------------------------------ uint8 value uint8 LESS_THAN_1_MINUTE = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg index 6e7d7fe65..11a49ee5b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg @@ -25,7 +25,16 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE StationaryVehicleContainer +# --- ASN.1 Definition --------------------------------------------------------- +# StationaryVehicleContainer ::= SEQUENCE { +# stationarySince StationarySince OPTIONAL, +# stationaryCause CauseCode OPTIONAL, +# carryingDangerousGoods DangerousGoodsExtended OPTIONAL, +# numberOfOccupants NumberOfOccupants OPTIONAL, +# vehicleIdentification VehicleIdentification OPTIONAL, +# energyStorageType EnergyStorageType OPTIONAL +# } +# ------------------------------------------------------------------------------ StationarySince stationary_since bool stationary_since_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg index 108080973..a970bdcb5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER StationaryVehicleSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# StationaryVehicleSubCauseCode ::= INTEGER {unavailable(0), humanProblem(1), vehicleBreakdown(2), postCrash(3), publicTransportStop(4), carryingDangerousGoods(5)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg index b38f81f0d..eb08c754b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE SteeringWheelAngle +# --- ASN.1 Definition --------------------------------------------------------- +# SteeringWheelAngle ::= SEQUENCE { +# steeringWheelAngleValue SteeringWheelAngleValue, +# steeringWheelAngleConfidence SteeringWheelAngleConfidence +# } +# ------------------------------------------------------------------------------ SteeringWheelAngleValue steering_wheel_angle_value SteeringWheelAngleConfidence steering_wheel_angle_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg index 7c3d46b9a..9c07b52b0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SteeringWheelAngleConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# SteeringWheelAngleConfidence ::= INTEGER {equalOrWithinOnePointFiveDegree (1), outOfRange(126), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg index c50be3980..aeae3ce54 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SteeringWheelAngleValue +# --- ASN.1 Definition --------------------------------------------------------- +# SteeringWheelAngleValue ::= INTEGER {straight(0), onePointFiveDegreesToRight(-1), onePointFiveDegreesToLeft(1), unavailable(512)} (-511..512) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -511 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg index 305bb683a..ebc0b6600 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER SubCauseCodeType +# --- ASN.1 Definition --------------------------------------------------------- +# SubCauseCodeType ::= INTEGER (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg index 09dc259a9..0a3e27072 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER Temperature +# --- ASN.1 Definition --------------------------------------------------------- +# Temperature ::= INTEGER {equalOrSmallerThanMinus60Deg (-60), oneDegreeCelsius(1), equalOrGreaterThan67Deg(67)} (-60..67) +# ------------------------------------------------------------------------------ int8 value int8 MIN = -60 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg index 04b1c59ce..ccdae355f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED Termination +# --- ASN.1 Definition --------------------------------------------------------- +# Termination ::= ENUMERATED {isCancellation(0), isNegation (1)} +# ------------------------------------------------------------------------------ uint8 value uint8 IS_CANCELLATION = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg index d8a0429ed..8366db355 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TimestampIts +# --- ASN.1 Definition --------------------------------------------------------- +# TimestampIts ::= INTEGER {utcStartOf2004(0), oneMillisecAfterUTCStartOf2004(1)} (0..4398046511103) +# ------------------------------------------------------------------------------ uint64 value uint64 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg index 5f5504458..f3a2e2a48 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE-OF Traces +# --- ASN.1 Definition --------------------------------------------------------- +# Traces ::= SEQUENCE SIZE(1..7) OF PathHistory +# ------------------------------------------------------------------------------ PathHistory[] array uint8 MIN_SIZE = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg index bf5bd835c..41b2503eb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TrafficConditionSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# TrafficConditionSubCauseCode ::= INTEGER {unavailable(0), increasedVolumeOfTraffic(1), trafficJamSlowlyIncreasing(2), trafficJamIncreasing(3), trafficJamStronglyIncreasing(4), trafficStationary(5), trafficJamSlightlyDecreasing(6), trafficJamDecreasing(7), trafficJamStronglyDecreasing(8)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg index 381da7c71..c688d0470 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg @@ -25,7 +25,10 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED TrafficRule .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# TrafficRule ::= ENUMERATED {noPassing(0), noPassingForTrucks(1), passToRight(2), passToLeft(3), ... +# } +# ------------------------------------------------------------------------------ uint8 value uint8 NO_PASSING = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg index a7edb7d27..e2f87591d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TransmissionInterval +# --- ASN.1 Definition --------------------------------------------------------- +# TransmissionInterval ::= INTEGER {oneMilliSecond(1), tenSeconds(10000)} (1..10000) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg index abab38688..510f64696 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER TurningRadius +# --- ASN.1 Definition --------------------------------------------------------- +# TurningRadius ::= INTEGER {point4Meters(1), unavailable(255)} (1..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg index 2a19a755b..6d5226ba7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## Ia5String VDS +# --- ASN.1 Definition --------------------------------------------------------- +# VDS ::= IA5String (SIZE(6)) +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg index a1c798831..9e069e511 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER ValidityDuration +# --- ASN.1 Definition --------------------------------------------------------- +# ValidityDuration ::= INTEGER {timeOfDetection(0), oneSecondAfterDetection(1)} (0..86400) +# ------------------------------------------------------------------------------ uint32 value uint32 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg index 1b76f5b68..814d2276a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleBreakdownSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleBreakdownSubCauseCode ::= INTEGER {unavailable(0), lackOfFuel (1), lackOfBatteryPower (2), engineProblem(3), transmissionProblem(4), engineCoolingProblem(5), brakingSystemProblem(6), steeringProblem(7), tyrePuncture(8), tyrePressureProblem(9)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg index ce86ece17..e43ea5841 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg @@ -25,7 +25,13 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE VehicleIdentification .extensible +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleIdentification ::= SEQUENCE { +# wMInumber WMInumber OPTIONAL, +# vDS VDS OPTIONAL, +# ... +# } +# ------------------------------------------------------------------------------ WMInumber w_m_inumber bool w_m_inumber_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg index 0efac770f..0b68fb8ef 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE VehicleLength +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleLength ::= SEQUENCE { +# vehicleLengthValue VehicleLengthValue, +# vehicleLengthConfidenceIndication VehicleLengthConfidenceIndication +# } +# ------------------------------------------------------------------------------ VehicleLengthValue vehicle_length_value VehicleLengthConfidenceIndication vehicle_length_confidence_indication diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg index b74b2519a..5b5d5d4c7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED VehicleLengthConfidenceIndication +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleLengthConfidenceIndication ::= ENUMERATED {noTrailerPresent(0), trailerPresentWithKnownLength(1), trailerPresentWithUnknownLength(2), trailerPresenceIsUnknown(3), unavailable(4)} +# ------------------------------------------------------------------------------ uint8 value uint8 NO_TRAILER_PRESENT = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg index 727323452..baed0b1ee 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleLengthValue +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleLengthValue ::= INTEGER {tenCentimeters(1), outOfRange(1022), unavailable(1023)} (1..1023) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg index d849f7995..986aab8fc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleMass +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleMass ::= INTEGER {hundredKg(1), unavailable(1024)} (1..1024) +# ------------------------------------------------------------------------------ uint16 value uint16 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg index c8aac5c89..3e089a89a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED VehicleRole +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleRole ::= ENUMERATED {default(0), publicTransport(1), specialTransport(2), dangerousGoods(3), roadWork(4), rescue(5), emergency(6), safetyCar(7), agriculture(8), commercial(9), military(10), roadOperator(11), taxi(12), reserved1(13), reserved2(14), reserved3(15)} +# ------------------------------------------------------------------------------ uint8 value uint8 DEFAULT = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg index a3f87bd07..b0a8e7fa5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VehicleWidth +# --- ASN.1 Definition --------------------------------------------------------- +# VehicleWidth ::= INTEGER {tenCentimeters(1), outOfRange(61), unavailable(62)} (1..62) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg index 51e0d5979..0ac4bda1a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE VerticalAcceleration +# --- ASN.1 Definition --------------------------------------------------------- +# VerticalAcceleration ::= SEQUENCE { +# verticalAccelerationValue VerticalAccelerationValue, +# verticalAccelerationConfidence AccelerationConfidence +# } +# ------------------------------------------------------------------------------ VerticalAccelerationValue vertical_acceleration_value AccelerationConfidence vertical_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg index 4a7a480e6..f0abb220c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER VerticalAccelerationValue +# --- ASN.1 Definition --------------------------------------------------------- +# VerticalAccelerationValue ::= INTEGER {pointOneMeterPerSecSquaredUp(1), pointOneMeterPerSecSquaredDown(-1), unavailable(161)} (-160 .. 161) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -160 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg index 4f15b48b3..072b549a6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg @@ -25,6 +25,8 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## Ia5String WMInumber +# --- ASN.1 Definition --------------------------------------------------------- +# WMInumber ::= IA5String (SIZE(1..3)) +# ------------------------------------------------------------------------------ string value diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg index 89fdb9ad3..0b7a691a5 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER WheelBaseVehicle +# --- ASN.1 Definition --------------------------------------------------------- +# WheelBaseVehicle ::= INTEGER {tenCentimeters(1), unavailable(127)} (1..127) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg index 900dbc587..a4611cb8c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER WrongWayDrivingSubCauseCode +# --- ASN.1 Definition --------------------------------------------------------- +# WrongWayDrivingSubCauseCode ::= INTEGER {unavailable(0), wrongLane(1), wrongDirection(2)} (0..255) +# ------------------------------------------------------------------------------ uint8 value uint8 MIN = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg index 404b07465..7305b6027 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg @@ -25,7 +25,12 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## SEQUENCE YawRate +# --- ASN.1 Definition --------------------------------------------------------- +# YawRate::= SEQUENCE { +# yawRateValue YawRateValue, +# yawRateConfidence YawRateConfidence +# } +# ------------------------------------------------------------------------------ YawRateValue yaw_rate_value YawRateConfidence yaw_rate_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg index 397121d65..a3a9eaab3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg @@ -25,7 +25,19 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## ENUMERATED YawRateConfidence +# --- ASN.1 Definition --------------------------------------------------------- +# YawRateConfidence ::= ENUMERATED { +# degSec-000-01 (0), +# degSec-000-05 (1), +# degSec-000-10 (2), +# degSec-001-00 (3), +# degSec-005-00 (4), +# degSec-010-00 (5), +# degSec-100-00 (6), +# outOfRange (7), +# unavailable (8) +# } +# ------------------------------------------------------------------------------ uint8 value uint8 DEG_SEC_000_01 = 0 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg index d3ebfedd5..3cf3b6b18 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg @@ -25,7 +25,9 @@ # --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- -## INTEGER YawRateValue +# --- ASN.1 Definition --------------------------------------------------------- +# YawRateValue ::= INTEGER {straight(0), degSec-000-01ToRight(-1), degSec-000-01ToLeft(1), unavailable(32767)} (-32766..32767) +# ------------------------------------------------------------------------------ int16 value int16 MIN = -32766 diff --git a/utils/codegen/codegen-rust/asn1ToRosMsg.py b/utils/codegen/codegen-rust/asn1ToRosMsg.py index 1a2fc6b78..ebc79b4e6 100755 --- a/utils/codegen/codegen-rust/asn1ToRosMsg.py +++ b/utils/codegen/codegen-rust/asn1ToRosMsg.py @@ -31,6 +31,7 @@ import shutil import subprocess import tempfile +from typing import Dict, List def parseCli(): """Parses script's CLI arguments. @@ -52,6 +53,45 @@ def parseCli(): return args +def asn1Definitions(files: List[str]) -> Dict[str, str]: + """Parses ASN1 files, extracts raw string definitions by type. + + Args: + files (List[str]): filepaths + + Returns: + Dict[str, str]]: raw string definition by type + """ + + asn1_raw = {} + for file in files: + with open(file) as f: + lines = f.readlines() + raw_def = None + for line in lines: + if "::=" in line: + if line.rstrip().endswith("{"): + type = line.split("::=")[0].split("{")[0].strip().split()[0] + raw_def = "" + elif len(line.split("::=")) == 2: + type = line.split("::=")[0].strip().split()[0] + if "}" in line or not ("{" in line or "}" in line): + raw_def = line + ros_type = type.replace("-", "") + asn1_raw[ros_type] = raw_def + raw_def = None + else: + raw_def = "" + if raw_def is not None: + raw_def += line + if "}" in line and not "}," in line and not ("::=" in line and line.rstrip().endswith("{")): + ros_type = type.replace("-", "") + asn1_raw[ros_type] = raw_def + raw_def = None + + return asn1_raw + + def main(): args = parseCli() @@ -79,6 +119,20 @@ def main(): # run rgen docker container to generate .msg files subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'msgs', ""], check=True) + # edit generated ROS .msg files to add ASN.1 raw definitions + asn1_raw = asn1Definitions(args.files) + for f in glob.glob(os.path.join(container_output_dir, "*.msg")): + with open(f, "r") as file: + msg = file.read() + for type, raw_def in asn1_raw.items(): + # add #'s to the beginning of the raw ASN.1 definition + commented_def = "# --- ASN.1 Definition ---------------------------------------------------------\n" +\ + "\n".join(["# " + line for line in raw_def.split('\n')][:-1]) + '\n' +\ + "# ------------------------------------------------------------------------------" + msg = re.sub(r"^##\s([\w-]+)\s" + type + r"\b", commented_def, msg, flags=re.MULTILINE) + with open(f, "w") as file: + file.write(msg) + # move generated ROS .msg files to output directories for f in glob.glob(os.path.join(container_output_dir, "*.msg")): shutil.move(f, os.path.join(args.output_dir, os.path.basename(f))) diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs index 2c88b0f33..cb5c52656 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs @@ -165,12 +165,12 @@ pub fn oid_template(_comments: &str, _name: &str, _annotations: &str) -> String pub fn enumerated_template( comments: &str, name: &str, - extensible: &str, + _extensible: &str, enum_members: &str, annotations: &str, ) -> String { licensed!(&format!( - "## ENUMERATED {name} {extensible}\n\ + "## ENUMERATED {name}\n\ {comments}\n\ uint8 value\n\ {enum_members}\n\ @@ -191,7 +191,7 @@ pub fn _sequence_or_set_value_template( pub fn sequence_or_set_template( comments: &str, name: &str, - extensible: &str, + _extensible: &str, members: &str, nested_members: Vec, annotations: &str, @@ -200,7 +200,7 @@ pub fn sequence_or_set_template( ) -> String { licensed!( &vec![ - &format!("## SEQUENCE {name} {extensible}"), + &format!("## SEQUENCE {name}"), comments, members, &nested_members.join("\n"), @@ -254,14 +254,14 @@ pub fn const_choice_value_template( pub fn choice_template( comments: &str, name: &str, - extensible: &str, + _extensible: &str, options: &str, nested_options: Vec, annotations: &str, ) -> String { licensed!( &vec![ - &format!("## CHOICE {name} {extensible}"), + &format!("## CHOICE {name}"), comments, "uint8 choice\n", options, From 39f69478972960bd36fcf2acbb567fb8976ab3d0 Mon Sep 17 00:00:00 2001 From: v0-e Date: Fri, 7 Jun 2024 10:46:49 +0100 Subject: [PATCH 16/22] rgen: Fix missing .msg constraints for some ASN.1 string types --- .../etsi_its_cam_conversion/convertActionID.h | 2 +- .../etsi_its_cam_conversion/convertAltitude.h | 2 +- .../convertBasicContainer.h | 2 +- ...onvertBasicVehicleContainerHighFrequency.h | 22 +++++++++---------- ...convertBasicVehicleContainerLowFrequency.h | 2 +- .../etsi_its_cam_conversion/convertCAM.h | 2 +- .../convertCamParameters.h | 2 +- .../convertClosedLanes.h | 2 +- .../convertCurvature.h | 2 +- .../convertDangerousGoodsExtended.h | 10 ++++----- .../convertDeltaReferencePosition.h | 2 +- .../convertEmergencyContainer.h | 2 +- .../convertEventPoint.h | 2 +- .../etsi_its_cam_conversion/convertHeading.h | 2 +- .../convertItineraryPath.h | 2 +- .../convertPositionOfPillars.h | 2 +- .../convertProtectedCommunicationZone.h | 6 ++--- .../convertProtectedCommunicationZonesRSU.h | 2 +- .../convertPtActivation.h | 2 +- .../convertPublicTransportContainer.h | 2 +- .../convertReferencePosition.h | 4 ++-- .../convertRestrictedTypes.h | 2 +- .../convertRoadWorksContainerBasic.h | 2 +- .../convertSafetyCarContainer.h | 2 +- .../convertSpecialVehicleContainer.h | 8 +++---- .../etsi_its_cam_conversion/convertSpeed.h | 2 +- .../convertSteeringWheelAngle.h | 2 +- .../etsi_its_cam_conversion/convertTraces.h | 2 +- .../convertVehicleIdentification.h | 2 +- .../convertVehicleLength.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../convertActionID.h | 2 +- .../convertAlacarteContainer.h | 6 ++--- .../convertAltitude.h | 2 +- .../convertCauseCode.h | 2 +- .../convertCenDsrcTollingZone.h | 2 +- .../convertCurvature.h | 2 +- .../convertDangerousGoodsExtended.h | 12 +++++----- ...tralizedEnvironmentalNotificationMessage.h | 2 +- .../convertEventPoint.h | 4 ++-- .../etsi_its_denm_conversion/convertHeading.h | 2 +- .../convertImpactReductionContainer.h | 10 ++++----- .../convertItineraryPath.h | 2 +- .../convertItsPduHeader.h | 2 +- .../convertLocationContainer.h | 2 +- .../convertManagementContainer.h | 8 +++---- .../convertPositionOfPillars.h | 2 +- .../convertProtectedCommunicationZone.h | 6 ++--- .../convertPtActivation.h | 2 +- .../convertReferenceDenms.h | 2 +- .../convertReferencePosition.h | 2 +- .../convertRoadWorksContainerExtended.h | 8 +++---- .../convertSituationContainer.h | 2 +- .../convertStationaryVehicleContainer.h | 6 ++--- .../convertVehicleIdentification.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../codegen-rust/rgen/src/msgs/builder.rs | 8 ++++--- .../codegen-rust/rgen/src/msgs/template.rs | 12 +++++----- 58 files changed, 109 insertions(+), 107 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index e175914bd..50b350be1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index b484e3bdc..b6ef74fe8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index 10ad0ce93..2c4552ed0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index afe8e42bf..1ae832dfd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -31,22 +31,22 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include +#include #include -#include -#include +#include #include +#include #include -#include +#include +#include +#include #include -#include #include -#include -#include -#include +#include +#include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index 7b861e103..fc2c42eac 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index 3d16361a5..45ad11a31 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -32,8 +32,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index ba794fd23..ae6050bd2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h index 93e235361..5346e8897 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 3e4ae6382..97035e124 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index 78a25f890..a60d7ccc2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -31,16 +31,16 @@ SOFTWARE. #pragma once #include -#include -#include #include -#include -#include -#include #include #include #include #include +#include +#include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index 3f5c5dbc3..dd5a8f3b0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index 6d2b71ead..687e41aeb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index 52d44e0d7..43fd203f1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index ecb6555c8..b99a2db20 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h index e10e262b1..87a4cacb3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 71cd8e11f..67344e0bf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index 775b3b379..99008e9e9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -31,12 +31,12 @@ SOFTWARE. #pragma once #include +#include #include #include -#include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index a9add2322..c03d39f8c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index ba43504cd..92ba34eb8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index d0f26b1e0..79be970e7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index 6e49d9e67..1a72a4d99 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -32,9 +32,9 @@ SOFTWARE. #include #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index c339b6461..28695a91b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index 99bcb0c7a..769751073 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index de3c9547a..85511d6ec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index e0c0c338c..b7d465dcb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -31,13 +31,13 @@ SOFTWARE. #pragma once #include -#include -#include -#include #include -#include +#include #include #include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index cae8c8c4b..31df3720c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index 86f948e53..65eadbd5e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index c95eb4a23..f5c40515c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index c2de949aa..2a7863712 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index 22a4e7b1c..0e941105e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index 5d216d34b..12ebeb807 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index efeb0c841..45591a1aa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 4dc6076f6..82cb9a7ae 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -31,11 +31,11 @@ SOFTWARE. #pragma once #include -#include -#include #include -#include +#include +#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index ed0d53e4b..9906518a7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index 29ee5a3e0..6e96d65b2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 75eaeb9b8..481ead265 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index 5b764c7a4..14d97441a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index 1c54b57d8..1c9e3fd43 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -31,16 +31,16 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include +#include #include #include +#include #include #include -#include -#include +#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index b971b5e32..19fe5b806 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #include #ifdef ROS1 diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index f2877b4ae..522716bb4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index e1f51d488..7d471774e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index 0c4d34971..152b41684 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -31,16 +31,16 @@ SOFTWARE. #pragma once #include -#include -#include -#include #include #include -#include -#include #include #include +#include +#include +#include +#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index 952e35f8d..efa1f46ee 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index 49ebcd336..cbeb01526 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -31,9 +31,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index fa1a0a7ff..1a8f00675 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -31,10 +31,10 @@ SOFTWARE. #pragma once #include -#include #include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index 1a4c6c44e..fbb663fea 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -31,15 +31,15 @@ SOFTWARE. #pragma once #include -#include +#include #include #include +#include #include -#include -#include #include +#include #include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h index 887a75980..e6bd20dcf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index 2bae62082..3c4b82ab5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -31,11 +31,11 @@ SOFTWARE. #pragma once #include -#include -#include -#include #include #include +#include +#include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index 83b8161b6..6cc429d2e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index 99329a621..b53e438ea 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -33,8 +33,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index 5bba96e43..90659a91e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -32,8 +32,8 @@ SOFTWARE. #include #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index 7ad596df9..0f2e84735 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -32,14 +32,14 @@ SOFTWARE. #include #include +#include +#include #include #include -#include -#include +#include #include #include -#include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index 20be3177f..f77985089 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -32,8 +32,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 1164c2a20..51d4941c0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -31,12 +31,12 @@ SOFTWARE. #pragma once #include +#include #include -#include -#include #include +#include +#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index f565b0169..7d768e433 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index 0426adc0b..9c6593ad6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -31,8 +31,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs index 50f644bee..95e30074e 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs @@ -187,11 +187,12 @@ pub fn generate_bit_string(tld: ToplevelTypeDefinition) -> Result Result { - if let ASN1Type::OctetString(ref _oct_str) = tld.ty { + if let ASN1Type::OctetString(ref oct_str) = tld.ty { Ok(octet_string_template( &format_comments(&tld.comments)?, &tld.name, - "", + &format_constraints(false, &oct_str.constraints)? + .replace("{prefix}", ""), )) } else { Err(GeneratorError::new( @@ -208,7 +209,8 @@ pub fn generate_character_string(tld: ToplevelTypeDefinition) -> Result String { +pub fn octet_string_template(comments: &str, name: &str, constraints: &str) -> String { format!( "## OCTET-STRING {name}\n\ {comments}\n\ uint8[] value\n\ - {annotations}" + {constraints}\n" ) } @@ -113,22 +113,22 @@ pub fn char_string_template( comments: &str, name: &str, string_type: &str, - annotations: &str, + constraints: &str, ) -> String { licensed!(&format!( "## {string_type} {name}\n\ {comments}\n\ string value\n\ - {annotations}" + {constraints}\n" )) } -pub fn boolean_template(comments: &str, name: &str, annotations: &str) -> String { +pub fn boolean_template(comments: &str, name: &str, constraints: &str) -> String { licensed!(&format!( "## BOOLEAN {name}\n\ {comments}\n\ bool value\n\ - {annotations}" + {constraints}\n" )) } From d8034bd0bfa11a192fc9b7510aa2b3962e15b067 Mon Sep 17 00:00:00 2001 From: v0-e Date: Fri, 7 Jun 2024 13:58:43 +0100 Subject: [PATCH 17/22] rgen: Add auto-gen info in helper .py scripts --- .../convertAccelerationConfidence.h | 3 -- .../convertAccelerationControl.h | 3 -- .../convertAccidentSubCauseCode.h | 3 -- .../etsi_its_cam_conversion/convertActionID.h | 5 +--- ...erseWeatherConditionAdhesionSubCauseCode.h | 3 -- ...itionExtremeWeatherConditionSubCauseCode.h | 3 -- ...eatherConditionPrecipitationSubCauseCode.h | 3 -- ...seWeatherConditionVisibilitySubCauseCode.h | 3 -- .../etsi_its_cam_conversion/convertAltitude.h | 3 -- .../convertAltitudeConfidence.h | 3 -- .../convertAltitudeValue.h | 3 -- .../convertBasicContainer.h | 5 +--- ...onvertBasicVehicleContainerHighFrequency.h | 25 +++++++--------- ...convertBasicVehicleContainerLowFrequency.h | 5 +--- .../etsi_its_cam_conversion/convertCAM.h | 4 --- .../convertCamParameters.h | 7 ++--- .../convertCauseCode.h | 3 -- .../convertCauseCodeType.h | 3 -- .../convertCenDsrcTollingZone.h | 7 ++--- .../convertCenDsrcTollingZoneID.h | 3 -- .../convertClosedLanes.h | 5 +--- .../convertCollisionRiskSubCauseCode.h | 3 -- .../convertCoopAwareness.h | 3 -- .../convertCurvature.h | 3 -- .../convertCurvatureCalculationMode.h | 3 -- .../convertCurvatureConfidence.h | 3 -- .../convertCurvatureValue.h | 3 -- .../convertDangerousEndOfQueueSubCauseCode.h | 3 -- .../convertDangerousGoodsBasic.h | 3 -- .../convertDangerousGoodsContainer.h | 3 -- .../convertDangerousGoodsExtended.h | 13 ++++----- .../convertDangerousSituationSubCauseCode.h | 3 -- .../convertDeltaAltitude.h | 3 -- .../convertDeltaLatitude.h | 3 -- .../convertDeltaLongitude.h | 3 -- .../convertDeltaReferencePosition.h | 5 +--- .../convertDigitalMap.h | 3 -- .../convertDriveDirection.h | 3 -- .../convertDrivingLaneStatus.h | 3 -- .../convertEmbarkationStatus.h | 3 -- .../convertEmergencyContainer.h | 3 -- .../convertEmergencyPriority.h | 3 -- ...tEmergencyVehicleApproachingSubCauseCode.h | 3 -- .../convertEnergyStorageType.h | 3 -- .../convertEventHistory.h | 5 +--- .../convertEventPoint.h | 5 +--- .../convertExteriorLights.h | 3 -- .../convertGenerationDeltaTime.h | 3 -- .../convertHardShoulderStatus.h | 3 -- ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 3 -- ...ardousLocationDangerousCurveSubCauseCode.h | 3 -- ...ousLocationObstacleOnTheRoadSubCauseCode.h | 3 -- ...dousLocationSurfaceConditionSubCauseCode.h | 3 -- .../etsi_its_cam_conversion/convertHeading.h | 3 -- .../convertHeadingConfidence.h | 3 -- .../convertHeadingValue.h | 3 -- .../convertHeightLonCarr.h | 3 -- .../convertHighFrequencyContainer.h | 5 +--- ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 3 -- .../convertHumanProblemSubCauseCode.h | 3 -- .../convertInformationQuality.h | 3 -- .../convertItineraryPath.h | 3 -- .../convertItsPduHeader.h | 5 +--- .../convertLanePosition.h | 3 -- .../convertLateralAcceleration.h | 5 +--- .../convertLateralAccelerationValue.h | 3 -- .../etsi_its_cam_conversion/convertLatitude.h | 3 -- .../convertLightBarSirenInUse.h | 3 -- .../convertLongitude.h | 3 -- .../convertLongitudinalAcceleration.h | 5 +--- .../convertLongitudinalAccelerationValue.h | 3 -- .../convertLowFrequencyContainer.h | 3 -- .../convertNumberOfOccupants.h | 3 -- .../convertOpeningDaysHours.h | 3 -- .../convertPathDeltaTime.h | 3 -- .../convertPathHistory.h | 5 +--- .../convertPathPoint.h | 5 +--- .../convertPerformanceClass.h | 3 -- .../convertPhoneNumber.h | 3 -- .../convertPosCentMass.h | 3 -- .../convertPosConfidenceEllipse.h | 5 +--- .../convertPosFrontAx.h | 3 -- .../convertPosLonCarr.h | 3 -- .../convertPosPillar.h | 3 -- .../convertPositionOfOccupants.h | 3 -- .../convertPositionOfPillars.h | 5 +--- .../convertPositioningSolutionType.h | 3 -- .../convertPostCrashSubCauseCode.h | 3 -- .../convertProtectedCommunicationZone.h | 11 +++---- .../convertProtectedCommunicationZonesRSU.h | 3 -- .../convertProtectedZoneID.h | 3 -- .../convertProtectedZoneRadius.h | 3 -- .../convertProtectedZoneType.h | 3 -- .../convertPtActivation.h | 3 -- .../convertPtActivationData.h | 3 -- .../convertPtActivationType.h | 3 -- .../convertPublicTransportContainer.h | 5 +--- .../convertRSUContainerHighFrequency.h | 3 -- .../convertReferencePosition.h | 7 ++--- .../convertRelevanceDistance.h | 3 -- .../convertRelevanceTrafficDirection.h | 3 -- .../convertRequestResponseIndication.h | 3 -- ...cueAndRecoveryWorkInProgressSubCauseCode.h | 3 -- .../convertRescueContainer.h | 3 -- .../convertRestrictedTypes.h | 5 +--- .../etsi_its_cam_conversion/convertRoadType.h | 3 -- .../convertRoadWorksContainerBasic.h | 5 +--- .../convertRoadworksSubCauseCode.h | 3 -- .../convertSafetyCarContainer.h | 5 +--- .../convertSemiAxisLength.h | 3 -- .../convertSequenceNumber.h | 3 -- .../convertSignalViolationSubCauseCode.h | 3 -- .../convertSlowVehicleSubCauseCode.h | 3 -- .../convertSpecialTransportContainer.h | 5 +--- .../convertSpecialTransportType.h | 3 -- .../convertSpecialVehicleContainer.h | 11 +++---- .../etsi_its_cam_conversion/convertSpeed.h | 5 +--- .../convertSpeedConfidence.h | 3 -- .../convertSpeedLimit.h | 3 -- .../convertSpeedValue.h | 3 -- .../convertStationID.h | 3 -- .../convertStationType.h | 3 -- .../convertStationarySince.h | 3 -- .../convertStationaryVehicleSubCauseCode.h | 3 -- .../convertSteeringWheelAngle.h | 5 +--- .../convertSteeringWheelAngleConfidence.h | 3 -- .../convertSteeringWheelAngleValue.h | 3 -- .../convertSubCauseCodeType.h | 3 -- .../convertTemperature.h | 3 -- .../convertTimestampIts.h | 3 -- .../etsi_its_cam_conversion/convertTraces.h | 5 +--- .../convertTrafficConditionSubCauseCode.h | 3 -- .../convertTrafficRule.h | 3 -- .../convertTransmissionInterval.h | 3 -- .../convertTurningRadius.h | 3 -- .../etsi_its_cam_conversion/convertVDS.h | 3 -- .../convertValidityDuration.h | 3 -- .../convertVehicleBreakdownSubCauseCode.h | 3 -- .../convertVehicleIdentification.h | 5 +--- .../convertVehicleLength.h | 3 -- ...convertVehicleLengthConfidenceIndication.h | 3 -- .../convertVehicleLengthValue.h | 3 -- .../convertVehicleMass.h | 3 -- .../convertVehicleRole.h | 3 -- .../convertVehicleWidth.h | 3 -- .../convertVerticalAcceleration.h | 3 -- .../convertVerticalAccelerationValue.h | 3 -- .../convertWMInumber.h | 3 -- .../convertWheelBaseVehicle.h | 3 -- .../convertWrongWayDrivingSubCauseCode.h | 3 -- .../etsi_its_cam_conversion/convertYawRate.h | 5 +--- .../convertYawRateConfidence.h | 3 -- .../convertYawRateValue.h | 3 -- .../convertAccelerationConfidence.h | 3 -- .../convertAccelerationControl.h | 3 -- .../convertAccidentSubCauseCode.h | 3 -- .../convertActionID.h | 5 +--- ...erseWeatherConditionAdhesionSubCauseCode.h | 3 -- ...itionExtremeWeatherConditionSubCauseCode.h | 3 -- ...eatherConditionPrecipitationSubCauseCode.h | 3 -- ...seWeatherConditionVisibilitySubCauseCode.h | 3 -- .../convertAlacarteContainer.h | 9 ++---- .../convertAltitude.h | 5 +--- .../convertAltitudeConfidence.h | 3 -- .../convertAltitudeValue.h | 3 -- .../convertCauseCode.h | 5 +--- .../convertCauseCodeType.h | 3 -- .../convertCenDsrcTollingZone.h | 5 +--- .../convertCenDsrcTollingZoneID.h | 3 -- .../convertClosedLanes.h | 3 -- .../convertCollisionRiskSubCauseCode.h | 3 -- .../convertCurvature.h | 3 -- .../convertCurvatureCalculationMode.h | 3 -- .../convertCurvatureConfidence.h | 3 -- .../convertCurvatureValue.h | 3 -- .../etsi_its_denm_conversion/convertDENM.h | 3 -- .../convertDangerousEndOfQueueSubCauseCode.h | 3 -- .../convertDangerousGoodsBasic.h | 3 -- .../convertDangerousGoodsExtended.h | 15 ++++------ .../convertDangerousSituationSubCauseCode.h | 3 -- ...tralizedEnvironmentalNotificationMessage.h | 5 +--- .../convertDeltaAltitude.h | 3 -- .../convertDeltaLatitude.h | 3 -- .../convertDeltaLongitude.h | 3 -- .../convertDeltaReferencePosition.h | 7 ++--- .../convertDigitalMap.h | 3 -- .../convertDriveDirection.h | 3 -- .../convertDrivingLaneStatus.h | 3 -- .../convertEmbarkationStatus.h | 3 -- .../convertEmergencyPriority.h | 3 -- ...tEmergencyVehicleApproachingSubCauseCode.h | 3 -- .../convertEnergyStorageType.h | 3 -- .../convertEventHistory.h | 3 -- .../convertEventPoint.h | 7 ++--- .../convertExteriorLights.h | 3 -- .../convertHardShoulderStatus.h | 3 -- ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 3 -- ...ardousLocationDangerousCurveSubCauseCode.h | 3 -- ...ousLocationObstacleOnTheRoadSubCauseCode.h | 3 -- ...dousLocationSurfaceConditionSubCauseCode.h | 3 -- .../etsi_its_denm_conversion/convertHeading.h | 3 -- .../convertHeadingConfidence.h | 3 -- .../convertHeadingValue.h | 3 -- .../convertHeightLonCarr.h | 3 -- ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 3 -- .../convertHumanProblemSubCauseCode.h | 3 -- .../convertImpactReductionContainer.h | 13 ++++----- .../convertInformationQuality.h | 3 -- .../convertItineraryPath.h | 3 -- .../convertItsPduHeader.h | 5 +--- .../convertLanePosition.h | 3 -- .../convertLateralAcceleration.h | 5 +--- .../convertLateralAccelerationValue.h | 3 -- .../convertLatitude.h | 3 -- .../convertLightBarSirenInUse.h | 3 -- .../convertLocationContainer.h | 5 +--- .../convertLongitude.h | 3 -- .../convertLongitudinalAcceleration.h | 5 +--- .../convertLongitudinalAccelerationValue.h | 3 -- .../convertManagementContainer.h | 13 ++++----- .../convertNumberOfOccupants.h | 3 -- .../convertOpeningDaysHours.h | 3 -- .../convertPathDeltaTime.h | 3 -- .../convertPathHistory.h | 3 -- .../convertPathPoint.h | 3 -- .../convertPerformanceClass.h | 3 -- .../convertPhoneNumber.h | 3 -- .../convertPosCentMass.h | 3 -- .../convertPosConfidenceEllipse.h | 3 -- .../convertPosFrontAx.h | 3 -- .../convertPosLonCarr.h | 3 -- .../convertPosPillar.h | 3 -- .../convertPositionOfOccupants.h | 3 -- .../convertPositionOfPillars.h | 5 +--- .../convertPositioningSolutionType.h | 3 -- .../convertPostCrashSubCauseCode.h | 3 -- .../convertProtectedCommunicationZone.h | 9 ++---- .../convertProtectedCommunicationZonesRSU.h | 5 +--- .../convertProtectedZoneID.h | 3 -- .../convertProtectedZoneRadius.h | 3 -- .../convertProtectedZoneType.h | 3 -- .../convertPtActivation.h | 5 +--- .../convertPtActivationData.h | 3 -- .../convertPtActivationType.h | 3 -- .../convertReferenceDenms.h | 5 +--- .../convertReferencePosition.h | 7 ++--- .../convertRelevanceDistance.h | 3 -- .../convertRelevanceTrafficDirection.h | 3 -- .../convertRequestResponseIndication.h | 3 -- ...cueAndRecoveryWorkInProgressSubCauseCode.h | 3 -- .../convertRestrictedTypes.h | 3 -- .../convertRoadType.h | 3 -- .../convertRoadWorksContainerExtended.h | 15 ++++------ .../convertRoadworksSubCauseCode.h | 3 -- .../convertSemiAxisLength.h | 3 -- .../convertSequenceNumber.h | 3 -- .../convertSignalViolationSubCauseCode.h | 3 -- .../convertSituationContainer.h | 7 ++--- .../convertSlowVehicleSubCauseCode.h | 3 -- .../convertSpecialTransportType.h | 3 -- .../etsi_its_denm_conversion/convertSpeed.h | 5 +--- .../convertSpeedConfidence.h | 3 -- .../convertSpeedLimit.h | 3 -- .../convertSpeedValue.h | 3 -- .../convertStationID.h | 3 -- .../convertStationType.h | 3 -- .../convertStationarySince.h | 3 -- .../convertStationaryVehicleContainer.h | 9 ++---- .../convertStationaryVehicleSubCauseCode.h | 3 -- .../convertSteeringWheelAngle.h | 3 -- .../convertSteeringWheelAngleConfidence.h | 3 -- .../convertSteeringWheelAngleValue.h | 3 -- .../convertSubCauseCodeType.h | 3 -- .../convertTemperature.h | 3 -- .../convertTermination.h | 3 -- .../convertTimestampIts.h | 3 -- .../etsi_its_denm_conversion/convertTraces.h | 5 +--- .../convertTrafficConditionSubCauseCode.h | 3 -- .../convertTrafficRule.h | 3 -- .../convertTransmissionInterval.h | 3 -- .../convertTurningRadius.h | 3 -- .../etsi_its_denm_conversion/convertVDS.h | 3 -- .../convertValidityDuration.h | 3 -- .../convertVehicleBreakdownSubCauseCode.h | 3 -- .../convertVehicleIdentification.h | 5 +--- .../convertVehicleLength.h | 5 +--- ...convertVehicleLengthConfidenceIndication.h | 3 -- .../convertVehicleLengthValue.h | 3 -- .../convertVehicleMass.h | 3 -- .../convertVehicleRole.h | 3 -- .../convertVehicleWidth.h | 3 -- .../convertVerticalAcceleration.h | 5 +--- .../convertVerticalAccelerationValue.h | 3 -- .../convertWMInumber.h | 3 -- .../convertWheelBaseVehicle.h | 3 -- .../convertWrongWayDrivingSubCauseCode.h | 3 -- .../etsi_its_denm_conversion/convertYawRate.h | 3 -- .../convertYawRateConfidence.h | 3 -- .../convertYawRateValue.h | 3 -- .../msg/EmbarkationStatus.msg | 1 + .../msg/OpeningDaysHours.msg | 1 + .../etsi_its_cam_msgs/msg/PhoneNumber.msg | 2 ++ .../msg/PtActivationData.msg | 29 +++++++++++++++++++ etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg | 1 + .../etsi_its_cam_msgs/msg/WMInumber.msg | 2 ++ .../msg/EmbarkationStatus.msg | 1 + .../msg/OpeningDaysHours.msg | 1 + .../etsi_its_denm_msgs/msg/PhoneNumber.msg | 2 ++ .../msg/PtActivationData.msg | 29 +++++++++++++++++++ etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg | 1 + .../etsi_its_denm_msgs/msg/WMInumber.msg | 2 ++ .../codegen-rust/asn1ToConversionHeader.py | 13 +++++++++ utils/codegen/codegen-rust/asn1ToRosMsg.py | 17 ++++++----- .../rgen/src/conversion/template.rs | 6 +--- .../codegen-rust/rgen/src/msgs/template.rs | 6 ++-- 315 files changed, 210 insertions(+), 1026 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h index 53e40b3ee..a03db7212 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AccelerationConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h index fc5aa8cbd..c6f025aef 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING AccelerationControl - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h index e293a6a81..570a2a065 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AccidentSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index 50b350be1..acf345253 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ActionID - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index e0b1b0cc2..9cbc90a7e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionAdhesionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 0c6c6e521..fc82ff237 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index 4c7bcaffb..572472b91 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionPrecipitationSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index be4ec702b..c3039da1d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionVisibilitySubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index b6ef74fe8..4ad1571e1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Altitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h index 6e618a11e..20dbdb5d8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED AltitudeConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h index 38b5c3703..a66df8160 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AltitudeValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index 2c4552ed0..a9a66fd62 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE BasicContainer - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index 1ae832dfd..9c068578e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -25,28 +25,25 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE BasicVehicleContainerHighFrequency - - #pragma once #include -#include -#include #include -#include -#include -#include -#include -#include +#include +#include +#include #include #include +#include +#include +#include +#include #include -#include +#include +#include +#include #include -#include -#include -#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index fc2c42eac..085859f36 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE BasicVehicleContainerLowFrequency - - #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index 45ad11a31..6df04f7d1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -25,10 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CAM -// The root data frame for cooperative awareness messages - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index ae6050bd2..42539a8b3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CamParameters - - #pragma once #include -#include -#include #include +#include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h index 63cad738f..f21cb38e9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h index 453ea9439..ae5d9cdce 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER CauseCodeType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index 15865e58d..f0b4bfef9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CenDsrcTollingZone - - #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h index 51cafb799..a630eb9d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// TYPEALIAS CenDsrcTollingZoneID - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h index 5346e8897..746e2a208 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ClosedLanes - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h index 89f8d13e0..b3cc50334 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER CollisionRiskSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h index 05183a579..7da611fc1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CoopAwareness - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 97035e124..07bd550fb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Curvature - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h index d6988a4f9..6416aea48 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED CurvatureCalculationMode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h index 60e133423..6ea542634 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED CurvatureConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h index 94d2f57b0..b600bef39 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER CurvatureValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h index c48ea0369..168301e6c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DangerousEndOfQueueSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h index 6366b41b6..523746aae 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED DangerousGoodsBasic - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h index da54b42af..40ba43d02 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DangerousGoodsContainer - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index a60d7ccc2..b9fa869c6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -25,22 +25,19 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DangerousGoodsExtended - - #pragma once #include +#include +#include #include +#include #include #include -#include -#include #include #include -#include -#include -#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h index 0ac42edf3..a60cdcfc7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DangerousSituationSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h index ae5d90d46..60640d42e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DeltaAltitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h index 9b4d2da4f..36371e8af 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DeltaLatitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h index 09d16fbfb..c78a8ddcf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DeltaLongitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index dd5a8f3b0..c116adef9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DeltaReferencePosition - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h index 15f387ae3..7fb57d071 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF DigitalMap - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h index cc5f20df3..a3a9fcb4e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED DriveDirection - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h index 213ab8ee6..523b50636 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING DrivingLaneStatus - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h index a09f47d99..2081e8643 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BOOLEAN EmbarkationStatus - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index 687e41aeb..c16208443 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE EmergencyContainer - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h index 175e7e63f..151742fcc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING EmergencyPriority - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index 3ae1c7e7e..f57ac9250 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER EmergencyVehicleApproachingSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h index fbb0d1c71..48bda7f58 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING EnergyStorageType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index 76971e076..792a45097 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF EventHistory - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index 43fd203f1..f5f058ed9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE EventPoint - - #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h index 3bd9655c0..ab6faf385 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING ExteriorLights - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h index c28c7cf77..d6b8aa77b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER GenerationDeltaTime - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h index 2dd8a4417..ced413a5b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED HardShoulderStatus - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index cb58cbb60..8bd242c16 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index b95fd2f20..98d76900e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationDangerousCurveSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index d4a5af23a..c24b31d49 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 9220c1a4a..0b91661b2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationSurfaceConditionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index b99a2db20..0ab06249e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Heading - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h index 9c8d4f5b5..2751c0b3e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HeadingConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h index 53ccd4c10..eaaeef13b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HeadingValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h index 8eba5cc41..018e67279 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HeightLonCarr - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h index d6da1fc9f..c39e7596d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// CHOICE HighFrequencyContainer - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index d7c69c507..15bfc07e0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HumanPresenceOnTheRoadSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h index ff6f3cb1d..19c72f33f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HumanProblemSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h index 993d5484f..25f05724e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER InformationQuality - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h index 87a4cacb3..3ac5ea98c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF ItineraryPath - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h index 73b19f160..f8ff33e30 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ItsPduHeader - - #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h index e17697960..76d7ce03f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER LanePosition - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index d0a505539..0562c2682 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE LateralAcceleration - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h index 842650580..0c1e76a3d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER LateralAccelerationValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h index 484c17f3c..378fde951 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER Latitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h index 01ad51b0c..99b0e1109 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING LightBarSirenInUse - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h index 45d06a556..816b730e6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER Longitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h index 73af8acaa..9a41880a4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE LongitudinalAcceleration - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h index b282e4c8a..1392c8e74 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER LongitudinalAccelerationValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h index 40ef0d5c2..31e624392 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// CHOICE LowFrequencyContainer - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h index a494b2680..5e3e2f797 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER NumberOfOccupants - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h index 9201690dd..06b61866d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// UTF8String OpeningDaysHours - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h index e474ed740..a8c1c3400 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PathDeltaTime - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h index 6a152a468..d5135b6ed 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF PathHistory - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index 60041f3ca..329233a2d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PathPoint - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h index e59256c2a..4247a000f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PerformanceClass - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h index c0df7132d..1ac9fffec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// NumericString PhoneNumber - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h index d105f9ebd..261089db7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosCentMass - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index be1b2d394..f60bb5b65 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PosConfidenceEllipse - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h index d2b282bbb..c058cfcd1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosFrontAx - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h index ed3ec6f33..7d127fe22 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosLonCarr - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h index 1b8818ebf..71a5c95bf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosPillar - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h index 9a3079bd2..0764a8a2d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING PositionOfOccupants - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 67344e0bf..448085ef4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF PositionOfPillars - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h index 6b47bea15..ea54fae60 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED PositioningSolutionType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h index 7ed80d1fc..aef888ec9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PostCrashSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index 99008e9e9..6a2e02d6d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -25,18 +25,15 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ProtectedCommunicationZone - - #pragma once #include -#include #include -#include -#include -#include #include +#include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index c03d39f8c..864ed05dd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF ProtectedCommunicationZonesRSU - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h index 52977161e..eaf9ef65f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER ProtectedZoneID - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h index dc894c2c0..2852508ee 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER ProtectedZoneRadius - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h index 26e7d8955..327d7709b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED ProtectedZoneType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index 92ba34eb8..d515af50c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PtActivation - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h index 1196423d2..40920b99f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// OCTET-STRING PtActivationData - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h index 1365dd16b..cef85430e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PtActivationType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index 79be970e7..0e505282d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PublicTransportContainer - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h index 72c932aa6..8b9fffcb9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE RSUContainerHighFrequency - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index 1a72a4d99..9c4db56bc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ReferencePosition - - #pragma once #include +#include +#include #include #include -#include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h index fe02f7977..73d7971d0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RelevanceDistance - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h index 531ae9eb9..00c73e547 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RelevanceTrafficDirection - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h index 2ebaf1630..2c9c8c854 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RequestResponseIndication - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index 092e472c4..ee851e760 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER RescueAndRecoveryWorkInProgressSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h index c533d691d..fc41c8961 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE RescueContainer - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index 28695a91b..f70b54f0e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF RestrictedTypes - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h index ecb66b71e..b39115f0f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RoadType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index 769751073..1e4c7f7aa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE RoadWorksContainerBasic - - #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h index 55d4c0d6a..892274129 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER RoadworksSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index 85511d6ec..e085c7318 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE SafetyCarContainer - - #pragma once #include +#include #include #include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h index c50816c7d..f30541b72 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SemiAxisLength - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h index fe596af03..db08cbb44 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SequenceNumber - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h index 308321ef4..00dc05ff3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SignalViolationSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h index 897ea247a..57f3b0c56 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SlowVehicleSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h index a299cf493..3eaa0f084 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE SpecialTransportContainer - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h index 2a59c08d3..3c16d029b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING SpecialTransportType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index b7d465dcb..57dbc9bbe 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -25,19 +25,16 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// CHOICE SpecialVehicleContainer - - #pragma once #include -#include +#include +#include #include +#include +#include #include #include -#include -#include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index 31df3720c..cb1f44022 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Speed - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h index c0ee1cd39..44aa34d2c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SpeedConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h index 8e6253b1e..0c92df001 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SpeedLimit - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h index fdce06cc7..66082b8c1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SpeedValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h index 2b939e9ab..7c3f10aa7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER StationID - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h index c10e555e2..41fd6a4e1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER StationType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h index 20695cccf..d892fce8b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED StationarySince - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h index 9a3585a07..5e19fb88f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER StationaryVehicleSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index 65eadbd5e..e76d88fdb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE SteeringWheelAngle - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h index 5bda9ff13..005f4baf2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SteeringWheelAngleConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h index 557ece0bc..d604f2ee0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SteeringWheelAngleValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h index f51866a5e..f59ea7c77 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SubCauseCodeType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h index 18f02776d..ec3f787e9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER Temperature - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h index 0cca9fbc6..37192c152 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TimestampIts - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index f5c40515c..6f7b385de 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF Traces - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h index e7b79d726..5b9b812bf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TrafficConditionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h index 80eab4581..2b339375a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED TrafficRule - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h index 679934de0..8791b61b9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TransmissionInterval - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h index 352ca56a5..27b9c851b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TurningRadius - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h index 726686d78..28471b4c8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// IA5String VDS - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h index aeda8ca93..667d26415 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER ValidityDuration - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h index d7cf4f7a9..7deb90d3f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleBreakdownSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index 2a7863712..fef5d71f0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE VehicleIdentification - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index 0e941105e..328748db2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE VehicleLength - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h index 39c7128e5..c449e4673 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED VehicleLengthConfidenceIndication - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h index a577dc92a..14745d64c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleLengthValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h index b16d9a03e..6b62da4ee 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleMass - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h index 5937bba66..604727281 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED VehicleRole - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h index 67d9eb129..642a3561b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleWidth - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index 12ebeb807..ee9e4d62b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE VerticalAcceleration - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h index 6eddf9109..62de438e2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VerticalAccelerationValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h index 68d80eb8f..681712d2d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// IA5String WMInumber - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h index 288b35fc7..3dd2ccfe0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER WheelBaseVehicle - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h index f642eae93..fa9da94ed 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER WrongWayDrivingSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index ba06a9005..2fc8887d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE YawRate - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h index d1ae9a21d..d650f6ac2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED YawRateConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h index 30d975955..f00935a2d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER YawRateValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h index 284acdc84..f38218e92 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AccelerationConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h index 7869a4434..5eef43e59 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING AccelerationControl - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h index 039001720..0135de6a9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AccidentSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index 45591a1aa..ed518f1da 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ActionID - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index e2e243c51..452e555c8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionAdhesionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index 1035ff79d..a763bc939 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionExtremeWeatherConditionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index 7e41ff671..d8890a145 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionPrecipitationSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index 2260f2908..a7330e543 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AdverseWeatherConditionVisibilitySubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 82cb9a7ae..848335152 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -25,18 +25,15 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE AlacarteContainer - - #pragma once #include -#include #include -#include -#include #include +#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index 9906518a7..3f71894cb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Altitude - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h index 9224e1c5c..2a5a8714c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED AltitudeConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h index 83a07854f..c6ceeda8a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER AltitudeValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index 6e96d65b2..f563edd6a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CauseCode - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h index 0c7b2144b..a9ff68ed2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER CauseCodeType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 481ead265..4ab38a53c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE CenDsrcTollingZone - - #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h index bd4c7c5a3..237b7a17e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// TYPEALIAS CenDsrcTollingZoneID - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index 1cc280bce..f9857a0f5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ClosedLanes - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h index 32c2fea9b..16a98951c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER CollisionRiskSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index 14d97441a..9da731375 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Curvature - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h index 20bd6caef..2dae5e459 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED CurvatureCalculationMode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h index 1999a1911..2ceda877e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED CurvatureConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h index c01039d5c..4105bf314 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER CurvatureValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h index 1f50131f4..7e248b153 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DENM - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h index f8e43bab1..24df0a6fd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DangerousEndOfQueueSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h index e0eb10ec2..925703055 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED DangerousGoodsBasic - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index 1c9e3fd43..2b665bef2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -25,22 +25,19 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DangerousGoodsExtended - - #pragma once #include -#include +#include +#include #include #include -#include -#include -#include #include #include -#include -#include +#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h index 18097be83..534fc9da3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DangerousSituationSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index 19fe5b806..fc783b65c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DecentralizedEnvironmentalNotificationMessage - - #pragma once #include -#include #include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h index cffb6919f..80b740f0a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DeltaAltitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h index f3a7e4aa1..55a4d8d3a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DeltaLatitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h index 859ee40b6..9ae00b60f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER DeltaLongitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index 36f00c6b9..6e00f2132 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE DeltaReferencePosition - - #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h index a8d4ce809..3ff0107d2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF DigitalMap - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h index d7d8960d9..03aa43dca 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED DriveDirection - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h index 7817d63fa..b22b025ce 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING DrivingLaneStatus - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h index 0c733f2af..cbe653daa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BOOLEAN EmbarkationStatus - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h index eecb38ae2..f72a36154 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING EmergencyPriority - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index dfa956d00..abc9966b0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER EmergencyVehicleApproachingSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h index bf45eb88b..0237f49b4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING EnergyStorageType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h index a454c3935..7fa8b2bc6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF EventHistory - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index 522716bb4..c41cca362 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE EventPoint - - #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h index 60eadeed6..a56ad554f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING ExteriorLights - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h index d19b4d4fe..1e21c3061 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED HardShoulderStatus - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 93fb07f64..5ca824213 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationAnimalOnTheRoadSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index b7d4f5b73..ef82abeea 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationDangerousCurveSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index bdb5e5b52..124c43bfb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationObstacleOnTheRoadSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 394f524aa..be0a55e58 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HazardousLocationSurfaceConditionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index 7d471774e..6dc709dbb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Heading - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h index 56fc14857..49581d239 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HeadingConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h index 36ea78709..5014bed18 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HeadingValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h index 59cc9045e..3c014cd18 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HeightLonCarr - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index 237e4937d..aa92d554a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HumanPresenceOnTheRoadSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h index b57002c7f..e3cff2980 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER HumanProblemSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index 152b41684..b2697e174 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -25,22 +25,19 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ImpactReductionContainer - - #pragma once #include #include +#include +#include +#include +#include +#include #include #include #include -#include -#include #include -#include -#include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h index d834c3135..dea5de12f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER InformationQuality - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index efa1f46ee..095f2e3f0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF ItineraryPath - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index cbeb01526..4acd87379 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ItsPduHeader - - #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h index 56311d2dd..a0b4d8796 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER LanePosition - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h index f3c9cf7f5..aa68d4e4c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE LateralAcceleration - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h index 322c34dd5..b30cf6bfc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER LateralAccelerationValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h index 0492e5d1c..06d959573 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER Latitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h index f220f7748..b471d7692 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING LightBarSirenInUse - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index 1a8f00675..b218114e7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE LocationContainer - - #pragma once #include #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h index 8e1c86666..85565e8c2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER Longitude - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index 8396df28e..1a0830c41 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE LongitudinalAcceleration - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h index a8785c950..a24bf9aa4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER LongitudinalAccelerationValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index fbb663fea..bf0839829 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -25,21 +25,18 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ManagementContainer - - #pragma once #include +#include #include -#include #include -#include -#include #include -#include #include -#include +#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h index 7cbade254..3f0170ba2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER NumberOfOccupants - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h index 4e2955db8..b8eb82f15 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// UTF8String OpeningDaysHours - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h index d21139adc..df8a582ef 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PathDeltaTime - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h index a218246e3..e88eb707f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF PathHistory - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index d2f972fe8..68f19c330 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PathPoint - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h index 500f259d7..b05653501 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PerformanceClass - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h index 27f41f14f..142620965 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// NumericString PhoneNumber - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h index 6b67b6541..001c472c9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosCentMass - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 66b770a62..79c1a5b40 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PosConfidenceEllipse - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h index 4df52b4b2..89c371eaa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosFrontAx - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h index 6ba9fc856..5eb681743 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosLonCarr - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h index 26e242863..9f24dae9a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PosPillar - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h index 00096bb86..4ab5de1a5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING PositionOfOccupants - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h index e6bd20dcf..409ba950c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF PositionOfPillars - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h index 18bc206b3..95696a013 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED PositioningSolutionType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h index 4aeb342d9..f2388a51e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PostCrashSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index 3c4b82ab5..bb70b5b55 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -25,18 +25,15 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ProtectedCommunicationZone - - #pragma once #include -#include -#include -#include #include +#include #include +#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h index 16f4ac4d6..836b8e3ae 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF ProtectedCommunicationZonesRSU - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h index abdffe796..510d52e00 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER ProtectedZoneID - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h index 82aa80137..817a26390 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER ProtectedZoneRadius - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h index dfa7ebde9..cfd7239a4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED ProtectedZoneType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index 6cc429d2e..6ffff2422 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE PtActivation - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h index 4ab3c185d..40412b152 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// OCTET-STRING PtActivationData - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h index f8a372d80..2ed6d70ec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER PtActivationType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index b53e438ea..c6a6a4682 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF ReferenceDenms - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index 90659a91e..fa84958d0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE ReferencePosition - - #pragma once #include -#include +#include #include +#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h index 87f2914bd..16b284d85 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RelevanceDistance - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h index 67ea2d4ba..685e4a0d3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RelevanceTrafficDirection - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h index 68f8b3b55..fe47f419c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RequestResponseIndication - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index b4a03f33d..0198db72e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER RescueAndRecoveryWorkInProgressSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h index 0823bf132..a9681f65f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF RestrictedTypes - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h index 692b8d147..4d29d4dcd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED RoadType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index 0f2e84735..d3c4dac23 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -25,21 +25,18 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE RoadWorksContainerExtended - - #pragma once #include -#include -#include -#include #include -#include -#include +#include +#include #include +#include +#include +#include #include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h index e1f254b4c..abde4d483 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER RoadworksSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h index 8b9dcc981..e0c0f53e3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SemiAxisLength - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h index 35de83560..4957b43f3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SequenceNumber - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h index 6d272841c..465b7ebcb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SignalViolationSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index f77985089..f6f72682a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -25,15 +25,12 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE SituationContainer - - #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h index a21c918f9..afad97176 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SlowVehicleSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h index 322cc4c2f..1bb17b9ac 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// BIT-STRING SpecialTransportType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index 2cc992f2a..39c118f21 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE Speed - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h index e40813fe9..563eac70e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SpeedConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h index 15ac2bd75..17c6c335c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SpeedLimit - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h index 72394204e..2ac727853 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SpeedValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h index 64e8d6287..18589bfbe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER StationID - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h index a67937635..be4e973d1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER StationType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h index 4e66545dc..0e731a731 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED StationarySince - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 51d4941c0..22951135f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -25,18 +25,15 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE StationaryVehicleContainer - - #pragma once #include #include -#include -#include #include -#include #include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h index 627a11ca9..354d6bfec 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER StationaryVehicleSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index 751f23cfb..f26826fcb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE SteeringWheelAngle - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h index c4d44243d..0105189c1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SteeringWheelAngleConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h index 33048b3c7..b78458562 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SteeringWheelAngleValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h index 0a13246d7..9375f23c5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER SubCauseCodeType - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h index acb7ce1ca..155709cdc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER Temperature - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h index a55ce6f5e..a83f40aef 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED Termination - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h index 00687d428..51d774356 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TimestampIts - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 7eadf0db7..3911ecb74 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -25,16 +25,13 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE-OF Traces - - #pragma once #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h index 7aa657675..d9710c2f8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TrafficConditionSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h index 55c3e6634..5020957db 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED TrafficRule - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h index bb0c73e8d..5d8039e67 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TransmissionInterval - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h index 904877c90..947206be2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER TurningRadius - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h index a73207bce..56823c949 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// IA5String VDS - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h index 8d2de77ce..995348d95 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER ValidityDuration - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h index f24915c47..6f8b7879e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleBreakdownSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index 7d768e433..cc27281fc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE VehicleIdentification - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index 68450ca58..11e153a5d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE VehicleLength - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h index a33571cd8..140c73392 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED VehicleLengthConfidenceIndication - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h index cd80ddc8e..637387766 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleLengthValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h index 2043cf65a..f83fcfefe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleMass - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h index 986ad3af1..acf882da9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED VehicleRole - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h index a7e54eaab..4b6e92059 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VehicleWidth - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index 9c6593ad6..6bc9a386a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -25,14 +25,11 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE VerticalAcceleration - - #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h index bea5bf0c1..482f4d24b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER VerticalAccelerationValue - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h index 2d17434fe..e9d128c8b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// IA5String WMInumber - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h index 1f1009943..465af2cc9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER WheelBaseVehicle - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h index 0efc0041d..3db1f845c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER WrongWayDrivingSubCauseCode - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h index b5090eb6e..c040f7010 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// SEQUENCE YawRate - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h index 693113711..fd49f1d0b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// ENUMERATED YawRateConfidence - - #pragma once #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h index 0e7b9f975..292d48400 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h @@ -25,9 +25,6 @@ SOFTWARE. // --- Auto-generated by asn1ToConversionHeader.py ----------------------------- -//// INTEGER YawRateValue - - #pragma once #include diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg index 6459d3da9..d0be1971f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg @@ -30,3 +30,4 @@ # ------------------------------------------------------------------------------ bool value + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg index ed47dd83f..3ca9fd400 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg @@ -30,3 +30,4 @@ # ------------------------------------------------------------------------------ string value + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg index 4406676ab..c905f4171 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg @@ -30,3 +30,5 @@ # ------------------------------------------------------------------------------ string value +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 16 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg index f0da8da3a..902dbf9e0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg @@ -1,5 +1,34 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + # --- ASN.1 Definition --------------------------------------------------------- # PtActivationData ::= OCTET STRING (SIZE(1..20)) # ------------------------------------------------------------------------------ uint8[] value +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 20 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg index 6d5226ba7..80ffff83c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg @@ -30,3 +30,4 @@ # ------------------------------------------------------------------------------ string value +uint8 SIZE = 6 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg index 072b549a6..22d1ceeab 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg @@ -30,3 +30,5 @@ # ------------------------------------------------------------------------------ string value +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 3 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg index 6459d3da9..d0be1971f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg @@ -30,3 +30,4 @@ # ------------------------------------------------------------------------------ bool value + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg index ed47dd83f..3ca9fd400 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg @@ -30,3 +30,4 @@ # ------------------------------------------------------------------------------ string value + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg index 4406676ab..c905f4171 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg @@ -30,3 +30,5 @@ # ------------------------------------------------------------------------------ string value +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 16 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg index f0da8da3a..902dbf9e0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg @@ -1,5 +1,34 @@ +# ============================================================================== +# MIT License +# +# Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University +# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in all +# copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +# SOFTWARE. +# ============================================================================== + +# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- + # --- ASN.1 Definition --------------------------------------------------------- # PtActivationData ::= OCTET STRING (SIZE(1..20)) # ------------------------------------------------------------------------------ uint8[] value +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 20 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg index 6d5226ba7..80ffff83c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg @@ -30,3 +30,4 @@ # ------------------------------------------------------------------------------ string value +uint8 SIZE = 6 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg index 072b549a6..22d1ceeab 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg @@ -30,3 +30,5 @@ # ------------------------------------------------------------------------------ string value +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 3 diff --git a/utils/codegen/codegen-rust/asn1ToConversionHeader.py b/utils/codegen/codegen-rust/asn1ToConversionHeader.py index dffd2b2e6..b45fdc690 100755 --- a/utils/codegen/codegen-rust/asn1ToConversionHeader.py +++ b/utils/codegen/codegen-rust/asn1ToConversionHeader.py @@ -80,6 +80,19 @@ def main(): # run rgen docker container to generate conversion headers subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'conversion-headers', args.message], check=True) + # add auto-gen info, remove in-file type and message name info (optional) + for f in glob.glob(os.path.join(container_output_dir, "*.h")): + with open(f, "r") as file: + msg = file.read() + + msg = re.sub(r"^////\s([\w-]+)\s.*\b", + "// --- Auto-generated by asn1ToConversionHeader.py -----------------------------", + msg, + flags=re.MULTILINE) + + with open(f, "w") as file: + file.write(msg) + # move generated conversion headers to output directories for f in glob.glob(os.path.join(container_output_dir, "*.h")): shutil.move(f, os.path.join(args.output_dir, os.path.basename(f))) diff --git a/utils/codegen/codegen-rust/asn1ToRosMsg.py b/utils/codegen/codegen-rust/asn1ToRosMsg.py index ebc79b4e6..48e2f03d0 100755 --- a/utils/codegen/codegen-rust/asn1ToRosMsg.py +++ b/utils/codegen/codegen-rust/asn1ToRosMsg.py @@ -119,17 +119,20 @@ def main(): # run rgen docker container to generate .msg files subprocess.run(["docker", "run", "--rm", "-u", f"{os.getuid()}:{os.getgid()}", "-v", f"{container_input_dir}:/input:ro", "-v", f"{container_output_dir}:/output", args.docker_image, 'msgs', ""], check=True) - # edit generated ROS .msg files to add ASN.1 raw definitions + # edit generated ROS .msg files to add auto-gen info, ASN.1 raw definitions (optional) asn1_raw = asn1Definitions(args.files) for f in glob.glob(os.path.join(container_output_dir, "*.msg")): with open(f, "r") as file: msg = file.read() - for type, raw_def in asn1_raw.items(): - # add #'s to the beginning of the raw ASN.1 definition - commented_def = "# --- ASN.1 Definition ---------------------------------------------------------\n" +\ - "\n".join(["# " + line for line in raw_def.split('\n')][:-1]) + '\n' +\ - "# ------------------------------------------------------------------------------" - msg = re.sub(r"^##\s([\w-]+)\s" + type + r"\b", commented_def, msg, flags=re.MULTILINE) + + type = os.path.basename(f).split('.')[0] + raw_def = asn1_raw[type] + comments = "# --- Auto-generated by asn1ToRosMsg.py ----------------------------------------\n\n" +\ + "# --- ASN.1 Definition ---------------------------------------------------------\n" +\ + "\n".join(["# " + line for line in raw_def.split('\n')][:-1]) + '\n' +\ + "# ------------------------------------------------------------------------------" + msg = re.sub(r"^##\s([\w-]+)\s" + type + r"\b", comments, msg, flags=re.MULTILINE) + with open(f, "w") as file: file.write(msg) diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/template.rs b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs index bc0c59091..414b48ebe 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs @@ -30,10 +30,7 @@ OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. ============================================================================= */ -// --- Auto-generated by asn1ToConversionHeader.py ----------------------------- - //// {asn1_type} {name} -{comments} #pragma once {extra-includes} @@ -63,7 +60,7 @@ void toStruct_{type}(const {pdu}_msgs::{ros_type}& in, {c_type}_t& out) { }"#; pub fn conversion_template( - comments: &str, + _comments: &str, pdu: &str, includes: &Vec, extra_includes: &Vec<&str>, @@ -116,7 +113,6 @@ pub fn conversion_template( ); CONVERSION_TEMPLATE - .replace("{comments}", comments) .replace("{extra-includes}", &extra_includes) .replace("{c_includes}", &c_includes) .replace("{ros1_includes}", &ros1_includes) diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs index 6f5a97a79..67f8b3374 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs @@ -24,8 +24,6 @@ r#"# =========================================================================== # SOFTWARE. # ============================================================================== -# --- Auto-generated by asn1ToRosMsg.py ---------------------------------------- - {definition}"#; macro_rules! licensed { @@ -101,12 +99,12 @@ pub fn bit_string_template(comments: &str, name: &str, constraints: &str, dvalue } pub fn octet_string_template(comments: &str, name: &str, constraints: &str) -> String { - format!( + licensed!(&format!( "## OCTET-STRING {name}\n\ {comments}\n\ uint8[] value\n\ {constraints}\n" - ) + )) } pub fn char_string_template( From e3171035c0b07ad609c1019737d1b4afd6ee15af Mon Sep 17 00:00:00 2001 From: v0-e Date: Tue, 11 Jun 2024 14:48:07 +0100 Subject: [PATCH 18/22] rgen: Unused code cleanup --- .../etsi_its_cam_conversion/convertAltitude.h | 2 +- ...onvertBasicVehicleContainerHighFrequency.h | 20 ++-- ...convertBasicVehicleContainerLowFrequency.h | 2 +- .../etsi_its_cam_conversion/convertCAM.h | 2 +- .../convertCamParameters.h | 4 +- .../convertCauseCode.h | 2 +- .../convertCenDsrcTollingZone.h | 2 +- .../convertCoopAwareness.h | 2 +- .../convertCurvature.h | 2 +- .../convertDangerousGoodsExtended.h | 2 +- .../convertDeltaReferencePosition.h | 2 +- .../convertEmergencyContainer.h | 2 +- .../convertEventHistory.h | 2 +- .../convertEventPoint.h | 2 +- .../convertHighFrequencyContainer.h | 2 +- .../convertLateralAcceleration.h | 2 +- .../convertLongitudinalAcceleration.h | 2 +- .../convertPositionOfPillars.h | 2 +- .../convertProtectedCommunicationZone.h | 6 +- .../convertPublicTransportContainer.h | 2 +- .../convertReferencePosition.h | 4 +- .../convertRoadWorksContainerBasic.h | 2 +- .../convertSafetyCarContainer.h | 2 +- .../convertSpecialVehicleContainer.h | 6 +- .../etsi_its_cam_conversion/convertSpeed.h | 2 +- .../convertSteeringWheelAngle.h | 2 +- .../etsi_its_cam_conversion/convertTraces.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../etsi_its_cam_conversion/convertYawRate.h | 2 +- .../convertAlacarteContainer.h | 8 +- .../convertAltitude.h | 2 +- .../convertCenDsrcTollingZone.h | 4 +- .../convertClosedLanes.h | 2 +- .../convertCurvature.h | 2 +- .../convertDangerousGoodsExtended.h | 12 +-- ...tralizedEnvironmentalNotificationMessage.h | 4 +- .../convertDeltaReferencePosition.h | 2 +- .../convertEventPoint.h | 2 +- .../convertImpactReductionContainer.h | 10 +- .../convertItsPduHeader.h | 2 +- .../convertLateralAcceleration.h | 2 +- .../convertLocationContainer.h | 4 +- .../convertLongitudinalAcceleration.h | 2 +- .../convertManagementContainer.h | 10 +- .../convertPathHistory.h | 2 +- .../convertPathPoint.h | 2 +- .../convertPosConfidenceEllipse.h | 2 +- .../convertProtectedCommunicationZone.h | 6 +- .../convertProtectedCommunicationZonesRSU.h | 2 +- .../convertPtActivation.h | 2 +- .../convertReferenceDenms.h | 2 +- .../convertReferencePosition.h | 4 +- .../convertRoadWorksContainerExtended.h | 8 +- .../convertSituationContainer.h | 2 +- .../etsi_its_denm_conversion/convertSpeed.h | 2 +- .../convertStationaryVehicleContainer.h | 4 +- .../convertSteeringWheelAngle.h | 2 +- .../etsi_its_denm_conversion/convertTraces.h | 2 +- .../convertVehicleIdentification.h | 2 +- .../codegen-rust/rgen/src/conversion/bin.rs | 2 - .../rgen/src/conversion/builder.rs | 73 ++------------- .../codegen-rust/rgen/src/conversion/mod.rs | 2 +- .../codegen-rust/rgen/src/conversion/utils.rs | 44 +-------- .../codegen-rust/rgen/src/msgs/builder.rs | 91 ++----------------- .../codegen-rust/rgen/src/msgs/template.rs | 3 - .../codegen-rust/rgen/src/msgs/utils.rs | 86 +----------------- 66 files changed, 121 insertions(+), 380 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index 4ad1571e1..b97b52246 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index 9c068578e..faf0f8fa1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -28,22 +28,22 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include -#include #include +#include #include +#include +#include +#include #include -#include +#include #include -#include -#include +#include #include -#include +#include +#include #include -#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index 085859f36..2ed4858a4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index 6df04f7d1..eb304dd64 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index 42539a8b3..c2b84ae7e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include #include -#include +#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h index f21cb38e9..99b1c25f0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index f0b4bfef9..490b64170 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h index 7da611fc1..7882bafdd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 07bd550fb..3876fe24a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index b9fa869c6..0bc6e4497 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #include #include #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index c116adef9..61f930ece 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index c16208443..f009ca73a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -29,8 +29,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index 792a45097..ea358a90b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index f5f058ed9..d7bef8ac3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h index c39e7596d..1544cc1d2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index 0562c2682..b4f47f525 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h index 9a41880a4..e2fe9ede9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 448085ef4..26939accf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index 6a2e02d6d..2d4c44ffe 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include -#include +#include #include -#include #include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index 0e505282d..613539d55 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index 9c4db56bc..d41201040 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include #include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index 1e4c7f7aa..744127584 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index e085c7318..91c333e70 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index 57dbc9bbe..7d4dddb2a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include -#include +#include #include -#include +#include #include #include -#include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index cb1f44022..080ed619c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index e76d88fdb..20f78c99c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index 6f7b385de..7d6722766 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index ee9e4d62b..bc2ba5339 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index 2fc8887d3..48df981b8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 848335152..53b16d1f1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include #include +#include #include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index 3f71894cb..222a28475 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 4ab38a53c..4f7a2d6b8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index f9857a0f5..ca064f0f4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index 9da731375..a1923c1d9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index 2b665bef2..36b7aef16 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -28,16 +28,16 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include #include #include +#include +#include +#include +#include #include #include -#include -#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index fc783b65c..434e00a03 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include +#include #include #include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index 6e00f2132..4bd4b0a8c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index c41cca362..08b2f5acd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index b2697e174..00d71a962 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -29,15 +29,15 @@ SOFTWARE. #include #include -#include -#include +#include #include -#include -#include #include -#include #include +#include +#include +#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index 4acd87379..d7c5e00be 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h index aa68d4e4c..b2d137132 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index b218114e7..1f82d2fde 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include +#include +#include #include #include -#include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index 1a0830c41..493f16207 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index bf0839829..dd3e2be3c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -28,15 +28,15 @@ SOFTWARE. #pragma once #include -#include #include -#include +#include +#include #include +#include #include -#include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h index e88eb707f..7aab1bcca 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index 68f19c330..101b9f0d9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 79c1a5b40..7495ddd84 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index bb70b5b55..63ba8b0f9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include -#include -#include -#include #include #include +#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h index 836b8e3ae..ba15baaf5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index 6ffff2422..4478efd76 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index c6a6a4682..72e1b1021 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index fa84958d0..4eb00c74a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include +#include #include +#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index d3c4dac23..8de410ab9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -28,14 +28,14 @@ SOFTWARE. #pragma once #include -#include -#include #include -#include #include +#include +#include +#include #include +#include #include -#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index f6f72682a..7ad7046ea 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -29,8 +29,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index 39c118f21..10963ddb8 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 22951135f..740dd8665 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include -#include #include -#include #include #include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index f26826fcb..b26524c4a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 3911ecb74..17f5d9abb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index cc27281fc..1928059bb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/bin.rs b/utils/codegen/codegen-rust/rgen/src/conversion/bin.rs index 26aca9af6..d6579e7ef 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/bin.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/bin.rs @@ -1,5 +1,3 @@ -use std::path::PathBuf; - use clap::Parser; use regex::Regex; diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/builder.rs b/utils/codegen/codegen-rust/rgen/src/conversion/builder.rs index 8a5e1a7c8..f2ae1106e 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/builder.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/builder.rs @@ -292,40 +292,15 @@ macro_rules! call_template { }; } -macro_rules! assignment { - ($unformatted:expr, $inner:expr) => {{ - let _ty = ($unformatted); - let _inner = $inner; - "quote!(#ty(#inner))".into() - }}; -} - pub fn generate_value(tld: ToplevelValueDefinition) -> Result { let ty = tld.associated_type.as_str(); match &tld.value { - ASN1Value::Null if ty == NULL => { - call_template!( - primitive_value_template, - tld, - "quote!(())".into(), - "quote!(())".into() - ) - } - ASN1Value::Null => call_template!( - primitive_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, "byte null 0".to_string()) - ), + ASN1Value::Null if ty == NULL => todo!(), + ASN1Value::Null => todo!(), ASN1Value::Boolean(b) if ty == BOOLEAN => { call_template!(primitive_value_template, tld, "bool", &b.to_string()) } - ASN1Value::Boolean(b) => call_template!( - primitive_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, b.to_string()) - ), + ASN1Value::Boolean(_) => todo!(), ASN1Value::LinkedIntValue { .. } => generate_integer_value(tld), ASN1Value::BitString(_) if ty == BIT_STRING => todo!(), ASN1Value::OctetString(_) if ty == OCTET_STRING => todo!(), @@ -365,24 +340,7 @@ pub fn generate_value(tld: ToplevelValueDefinition) -> Result, _>>()?; todo!() } - ASN1Value::LinkedNestedValue { supertypes, value } => { - let parent = supertypes.last().map(|s| (s)); - if value.is_const_type() { - call_template!( - primitive_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) - ) - } else { - call_template!( - lazy_static_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) - ) - } - } + ASN1Value::LinkedNestedValue { .. } => todo!(), ASN1Value::ObjectIdentifier(_) if ty == OBJECT_IDENTIFIER => todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == NUMERIC_STRING => todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == VISIBLE_STRING => todo!(), @@ -391,32 +349,15 @@ pub fn generate_value(tld: ToplevelValueDefinition) -> Result todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == PRINTABLE_STRING => todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == GENERAL_STRING => todo!(), - ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SEQUENCE_OF) => { - let _item_type = format_sequence_or_set_of_item_type( - ty.replace(SEQUENCE_OF, "").trim().to_string(), - s.first().map(|i| &**i), - ); - todo!() - } - ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SET_OF) => { - let _item_type = format_sequence_or_set_of_item_type( - ty.replace(SET_OF, "").trim().to_string(), - s.first().map(|i| &**i), - ); - todo!() - } + ASN1Value::LinkedArrayLikeValue(_) if ty.contains(SEQUENCE_OF) => todo!(), + ASN1Value::LinkedArrayLikeValue(_) if ty.contains(SET_OF) => todo!(), ASN1Value::BitString(_) | ASN1Value::Time(_) | ASN1Value::LinkedCharStringValue(_, _) | ASN1Value::ObjectIdentifier(_) | ASN1Value::LinkedArrayLikeValue(_) | ASN1Value::ElsewhereDeclaredValue { .. } - | ASN1Value::OctetString(_) => call_template!( - lazy_static_value_template, - tld, - &tld.associated_type.to_string(), - assignment!(&tld.associated_type, value_to_tokens(&tld.value, None)?) - ), + | ASN1Value::OctetString(_) => todo!(), _ => Ok("".to_string()), } } diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/mod.rs b/utils/codegen/codegen-rust/rgen/src/conversion/mod.rs index 5a42fb498..ee1ff75b5 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/mod.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/mod.rs @@ -50,7 +50,7 @@ fn generate( ASN1Type::ElsewhereDeclaredType(_) => generate_typealias(&options, t), ASN1Type::Choice(_) => generate_choice(&options, t), ASN1Type::OctetString(_) => generate_octet_string(&options, t), - ASN1Type::Time(_) => unimplemented!("rasn does not support TIME types yet!"), + ASN1Type::Time(_) => unimplemented!("TIME types are currently unsupported!"), ASN1Type::Real(_) => Err(GeneratorError { kind: GeneratorErrorType::NotYetInplemented, details: "Real types are currently unsupported!".into(), diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/utils.rs b/utils/codegen/codegen-rust/rgen/src/conversion/utils.rs index d89de6af4..65d36720f 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/utils.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/utils.rs @@ -336,7 +336,7 @@ pub fn value_to_tokens( } } -pub fn format_sequence_or_set_of_item_type( +pub fn _format_sequence_or_set_of_item_type( type_name: String, first_item: Option<&ASN1Value>, ) -> String { @@ -366,45 +366,3 @@ pub fn format_sequence_or_set_of_item_type( name => name, } } - -trait ASN1ValueExt { - fn is_const_type(&self) -> bool; -} - -impl ASN1ValueExt for ASN1Value { - fn is_const_type(&self) -> bool { - match self { - ASN1Value::Null | ASN1Value::Boolean(_) | ASN1Value::EnumeratedValue { .. } => true, - ASN1Value::Choice { inner_value, .. } => inner_value.is_const_type(), - ASN1Value::LinkedIntValue { integer_type, .. } => { - integer_type != &IntegerType::Unbounded - } - ASN1Value::LinkedNestedValue { value, .. } => value.is_const_type(), - ASN1Value::LinkedElsewhereDefinedValue { can_be_const, .. } => *can_be_const, - _ => false, - } - } -} - -impl ASN1ValueExt for ASN1Type { - fn is_const_type(&self) -> bool { - match self { - ASN1Type::Null | ASN1Type::Enumerated(_) | ASN1Type::Boolean(_) => true, - ASN1Type::Integer(i) => { - i.constraints.iter().fold(IntegerType::Unbounded, |acc, c| { - acc.max_restrictive(c.integer_constraints()) - }) != IntegerType::Unbounded - } - ASN1Type::Choice(c) => c - .options - .iter() - .fold(true, |acc, opt| opt.ty.is_const_type() && acc), - ASN1Type::Set(s) | ASN1Type::Sequence(s) => s - .members - .iter() - .fold(true, |acc, m| m.ty.is_const_type() && acc), - ASN1Type::SetOf(s) | ASN1Type::SequenceOf(s) => s.element_type.is_const_type(), - _ => false, - } - } -} diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs index 95e30074e..93b4ae218 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/builder.rs @@ -247,14 +247,6 @@ macro_rules! call_template { }; } -macro_rules! assignment { - ($unformatted:expr, $inner:expr) => {{ - let _ty = ($unformatted); - let _inner = $inner; - "quote!(#ty(#inner))".into() - }}; -} - pub fn generate_value(tld: ToplevelValueDefinition) -> Result { let ty = tld.associated_type.as_str(); match &tld.value { @@ -266,21 +258,11 @@ pub fn generate_value(tld: ToplevelValueDefinition) -> Result call_template!( - primitive_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, "byte null 0".to_string()) - ), + ASN1Value::Null => todo!(), ASN1Value::Boolean(b) if ty == BOOLEAN => { call_template!(primitive_value_template, tld, "bool", &b.to_string()) } - ASN1Value::Boolean(b) => call_template!( - primitive_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, b.to_string()) - ), + ASN1Value::Boolean(_) => todo!(), ASN1Value::LinkedIntValue { .. } => generate_integer_value(tld), ASN1Value::BitString(_) if ty == BIT_STRING => todo!(), ASN1Value::OctetString(_) if ty == OCTET_STRING => todo!(), @@ -313,31 +295,8 @@ pub fn generate_value(tld: ToplevelValueDefinition) -> Result call_template!(enum_value_template, tld, enumerated, enumerable), ASN1Value::Time(_) if ty == GENERALIZED_TIME => todo!(), ASN1Value::Time(_) if ty == UTC_TIME => todo!(), - ASN1Value::LinkedStructLikeValue(s) => { - let _members = s - .iter() - .map(|(_, _, val)| value_to_tokens(val.value(), None)) - .collect::, _>>()?; - todo!() - } - ASN1Value::LinkedNestedValue { supertypes, value } => { - let parent = supertypes.last().map(|s| (s)); - if value.is_const_type() { - call_template!( - primitive_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) - ) - } else { - call_template!( - lazy_static_value_template, - tld, - &tld.associated_type, - assignment!(&tld.associated_type, value_to_tokens(&tld.value, parent)?) - ) - } - } + ASN1Value::LinkedStructLikeValue(_) => todo!(), + ASN1Value::LinkedNestedValue { .. } => todo!(), ASN1Value::ObjectIdentifier(_) if ty == OBJECT_IDENTIFIER => todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == NUMERIC_STRING => todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == VISIBLE_STRING => todo!(), @@ -346,32 +305,15 @@ pub fn generate_value(tld: ToplevelValueDefinition) -> Result todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == PRINTABLE_STRING => todo!(), ASN1Value::LinkedCharStringValue(_, _) if ty == GENERAL_STRING => todo!(), - ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SEQUENCE_OF) => { - let _item_type = format_sequence_or_set_of_item_type( - ty.replace(SEQUENCE_OF, "").trim().to_string(), - s.first().map(|i| &**i), - ); - todo!() - } - ASN1Value::LinkedArrayLikeValue(s) if ty.contains(SET_OF) => { - let _item_type = format_sequence_or_set_of_item_type( - ty.replace(SET_OF, "").trim().to_string(), - s.first().map(|i| &**i), - ); - todo!() - } + ASN1Value::LinkedArrayLikeValue(_) if ty.contains(SEQUENCE_OF) => todo!(), + ASN1Value::LinkedArrayLikeValue(_) if ty.contains(SET_OF) => todo!(), ASN1Value::BitString(_) | ASN1Value::Time(_) | ASN1Value::LinkedCharStringValue(_, _) | ASN1Value::ObjectIdentifier(_) | ASN1Value::LinkedArrayLikeValue(_) | ASN1Value::ElsewhereDeclaredValue { .. } - | ASN1Value::OctetString(_) => call_template!( - lazy_static_value_template, - tld, - &tld.associated_type.to_string(), - assignment!(&tld.associated_type, value_to_tokens(&tld.value, None)?) - ), + | ASN1Value::OctetString(_) => todo!(), _ => Ok("".to_string()), } } @@ -450,14 +392,9 @@ pub fn generate_null(tld: ToplevelTypeDefinition) -> Result Result { if let ASN1Type::Enumerated(ref enumerated) = tld.ty { - let extensible = enumerated - .extensible - .map(|_| ".extensible".into()) - .unwrap_or_default(); Ok(enumerated_template( &format_comments(&tld.comments)?, &tld.name, - extensible, &format_enum_members(enumerated), "", )) @@ -473,14 +410,9 @@ pub fn generate_enumerated(tld: ToplevelTypeDefinition) -> Result Result { if let ASN1Type::Choice(ref choice) = tld.ty { let inner_options = format_nested_choice_options(choice, &tld.name)?; - let extensible = choice - .extensible - .map(|_| ".extensible".into()) - .unwrap_or_default(); Ok(choice_template( &format_comments(&tld.comments)?, &tld.name, - extensible, &format_choice_options(choice, &tld.name)?, inner_options, "", @@ -497,15 +429,10 @@ pub fn generate_choice(tld: ToplevelTypeDefinition) -> Result Result { match tld.ty { ASN1Type::Sequence(ref seq) | ASN1Type::Set(ref seq) => { - let extensible = seq - .extensible - .map(|_| ".extensible".into()) - .unwrap_or_default(); let declaration = format_sequence_or_set_members(seq, &tld.name)?; Ok(sequence_or_set_template( &format_comments(&tld.comments)?, &tld.name, - extensible, &declaration, format_nested_sequence_members(seq, &tld.name)?, "", @@ -653,7 +580,7 @@ pub fn generate_information_object_set( } => { let _tokenized_value = value_to_tokens(id, Some(&class_unique_id_type_name))?; - "quote!(*#tokenized_value)".into() + todo!() } ASN1Value::LinkedNestedValue { value, .. } if matches![ @@ -666,7 +593,7 @@ pub fn generate_information_object_set( { let _tokenized_value = value_to_tokens(value, Some(&class_unique_id_type_name))?; - "quote!(*#tokenized_value)".into() + todo!() } ASN1Value::LinkedNestedValue { value, .. } if matches![&**value, ASN1Value::LinkedElsewhereDefinedValue { .. }] => diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs index 67f8b3374..423653da9 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/template.rs @@ -163,7 +163,6 @@ pub fn oid_template(_comments: &str, _name: &str, _annotations: &str) -> String pub fn enumerated_template( comments: &str, name: &str, - _extensible: &str, enum_members: &str, annotations: &str, ) -> String { @@ -189,7 +188,6 @@ pub fn _sequence_or_set_value_template( pub fn sequence_or_set_template( comments: &str, name: &str, - _extensible: &str, members: &str, nested_members: Vec, annotations: &str, @@ -252,7 +250,6 @@ pub fn const_choice_value_template( pub fn choice_template( comments: &str, name: &str, - _extensible: &str, options: &str, nested_options: Vec, annotations: &str, diff --git a/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs b/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs index 15829c722..527da63be 100644 --- a/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs +++ b/utils/codegen/codegen-rust/rgen/src/msgs/utils.rs @@ -1,9 +1,7 @@ use crate::common::{to_ros_const_case, to_ros_snake_case, to_ros_title_case, IntegerTypeExt}; use rasn_compiler::intermediate::{ constraints::Constraint, - encoding_rules::per_visible::{ - per_visible_range_constraints, CharsetSubset, PerVisibleAlphabetConstraints, - }, + encoding_rules::per_visible::per_visible_range_constraints, information_object::{InformationObjectClass, InformationObjectField}, types::{Choice, ChoiceOption, Enumerated, SequenceOrSet, SequenceOrSetMember}, ASN1Type, ASN1Value, CharacterStringType, IntegerType, ToplevelDefinition, @@ -162,40 +160,6 @@ pub fn format_distinguished_values(dvalues: &Option>) -> result } -pub fn _format_alphabet_annotations( - string_type: CharacterStringType, - constraints: &Vec, -) -> Result { - if constraints.is_empty() { - return Ok("".into()); - } - let mut permitted_alphabet = PerVisibleAlphabetConstraints::default_for(string_type); - for c in constraints { - if let Some(mut p) = PerVisibleAlphabetConstraints::try_new(c, string_type)? { - permitted_alphabet += &mut p - } - } - permitted_alphabet.finalize(); - let alphabet_unicode = permitted_alphabet - .charset_subsets() - .iter() - .map(|subset| match subset { - CharsetSubset::Single(c) => format!("{}", c.escape_unicode()), - CharsetSubset::Range { from, to } => format!( - "{}..{}", - from.map_or(String::from(""), |c| format!("{}", c.escape_unicode())), - to.map_or(String::from(""), |c| format!("{}", c.escape_unicode())) - ), - }) - .collect::>() - .join(", "); - Ok(if alphabet_unicode.is_empty() { - "".into() - } else { - "from(#alphabet_unicode)".into() - }) -} - pub fn format_enum_members(enumerated: &Enumerated) -> String { let first_extension_index = enumerated.extensible; enumerated @@ -462,9 +426,7 @@ pub fn type_to_tokens(ty: &ASN1Type) -> Result { ASN1Type::GeneralizedTime(_) => Ok("GeneralizedTime".into()), ASN1Type::UTCTime(_) => Ok("UtcTime".into()), ASN1Type::EmbeddedPdv | ASN1Type::External => Ok("Any".into()), - ASN1Type::ChoiceSelectionType(c) => { - let _choice = &c.choice_name; - let _option = &c.selected_option; + ASN1Type::ChoiceSelectionType(_) => { todo!() } } @@ -656,7 +618,7 @@ pub fn format_nested_choice_options( .collect::, _>>() } -pub fn format_sequence_or_set_of_item_type( +pub fn _format_sequence_or_set_of_item_type( type_name: String, first_item: Option<&ASN1Value>, ) -> String { @@ -743,45 +705,3 @@ pub fn resolve_standard_syntax( }), } } - -trait ASN1ValueExt { - fn is_const_type(&self) -> bool; -} - -impl ASN1ValueExt for ASN1Value { - fn is_const_type(&self) -> bool { - match self { - ASN1Value::Null | ASN1Value::Boolean(_) | ASN1Value::EnumeratedValue { .. } => true, - ASN1Value::Choice { inner_value, .. } => inner_value.is_const_type(), - ASN1Value::LinkedIntValue { integer_type, .. } => { - integer_type != &IntegerType::Unbounded - } - ASN1Value::LinkedNestedValue { value, .. } => value.is_const_type(), - ASN1Value::LinkedElsewhereDefinedValue { can_be_const, .. } => *can_be_const, - _ => false, - } - } -} - -impl ASN1ValueExt for ASN1Type { - fn is_const_type(&self) -> bool { - match self { - ASN1Type::Null | ASN1Type::Enumerated(_) | ASN1Type::Boolean(_) => true, - ASN1Type::Integer(i) => { - i.constraints.iter().fold(IntegerType::Unbounded, |acc, c| { - acc.max_restrictive(c.integer_constraints()) - }) != IntegerType::Unbounded - } - ASN1Type::Choice(c) => c - .options - .iter() - .fold(true, |acc, opt| opt.ty.is_const_type() && acc), - ASN1Type::Set(s) | ASN1Type::Sequence(s) => s - .members - .iter() - .fold(true, |acc, m| m.ty.is_const_type() && acc), - ASN1Type::SetOf(s) | ASN1Type::SequenceOf(s) => s.element_type.is_const_type(), - _ => false, - } - } -} From 6de121fca3aa2c0e74288107948c70d200e60b8e Mon Sep 17 00:00:00 2001 From: v0-e Date: Tue, 11 Jun 2024 14:59:44 +0100 Subject: [PATCH 19/22] rgen: Sort conversion C includes --- .../etsi_its_cam_conversion/convertActionID.h | 2 +- .../convertBasicContainer.h | 2 +- ...onvertBasicVehicleContainerHighFrequency.h | 22 +++++++++---------- ...convertBasicVehicleContainerLowFrequency.h | 4 ++-- .../convertCamParameters.h | 4 ++-- .../convertCenDsrcTollingZone.h | 2 +- .../convertCurvature.h | 2 +- .../convertDangerousGoodsExtended.h | 12 +++++----- .../convertDeltaReferencePosition.h | 2 +- .../convertEmergencyContainer.h | 4 ++-- .../convertEventHistory.h | 2 +- .../convertEventPoint.h | 4 ++-- .../convertItineraryPath.h | 2 +- .../convertLateralAcceleration.h | 2 +- .../convertPathHistory.h | 2 +- .../convertPathPoint.h | 2 +- .../convertPosConfidenceEllipse.h | 2 +- .../convertPositionOfPillars.h | 2 +- .../convertProtectedCommunicationZone.h | 2 +- .../convertProtectedCommunicationZonesRSU.h | 2 +- .../convertPtActivation.h | 2 +- .../convertReferencePosition.h | 4 ++-- .../convertRoadWorksContainerBasic.h | 4 ++-- .../convertSafetyCarContainer.h | 4 ++-- .../convertSpecialVehicleContainer.h | 8 +++---- .../convertSteeringWheelAngle.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../etsi_its_cam_conversion/convertYawRate.h | 2 +- .../convertAlacarteContainer.h | 4 ++-- .../convertAltitude.h | 2 +- .../convertCauseCode.h | 2 +- .../convertCenDsrcTollingZone.h | 2 +- .../convertClosedLanes.h | 2 +- .../etsi_its_denm_conversion/convertDENM.h | 2 +- .../convertDangerousGoodsExtended.h | 12 +++++----- ...tralizedEnvironmentalNotificationMessage.h | 2 +- .../convertDeltaReferencePosition.h | 4 ++-- .../convertEventPoint.h | 2 +- .../convertImpactReductionContainer.h | 14 ++++++------ .../convertItineraryPath.h | 2 +- .../convertItsPduHeader.h | 2 +- .../convertLocationContainer.h | 4 ++-- .../convertManagementContainer.h | 12 +++++----- .../convertPathHistory.h | 2 +- .../convertPathPoint.h | 2 +- .../convertPosConfidenceEllipse.h | 2 +- .../convertProtectedCommunicationZone.h | 6 ++--- .../convertProtectedCommunicationZonesRSU.h | 2 +- .../convertPtActivation.h | 2 +- .../convertReferenceDenms.h | 2 +- .../convertReferencePosition.h | 4 ++-- .../convertRoadWorksContainerExtended.h | 8 +++---- .../convertSituationContainer.h | 2 +- .../etsi_its_denm_conversion/convertSpeed.h | 2 +- .../convertStationaryVehicleContainer.h | 6 ++--- .../etsi_its_denm_conversion/convertTraces.h | 2 +- .../convertVehicleLength.h | 2 +- .../convertVerticalAcceleration.h | 2 +- .../rgen/src/conversion/template.rs | 7 +++--- 59 files changed, 114 insertions(+), 113 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index acf345253..67d3830ef 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index a9a66fd62..d763f1637 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index faf0f8fa1..53f8708c4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -28,22 +28,22 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include +#include #include -#include -#include -#include -#include +#include #include +#include +#include +#include #include -#include -#include +#include +#include +#include +#include +#include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index 2ed4858a4..86fa46ef7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index c2b84ae7e..76379d811 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index 490b64170..86ca6085b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 3876fe24a..07bd550fb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index 0bc6e4497..f4741d2d2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -28,16 +28,16 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include -#include -#include #include #include #include #include +#include +#include +#include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index 61f930ece..f67e0be79 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -29,8 +29,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index f009ca73a..c8b08283e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index ea358a90b..792a45097 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index d7bef8ac3..3b28875d0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h index 3ac5ea98c..c30af34f9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index b4f47f525..0562c2682 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h index d5135b6ed..d043a9530 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index 329233a2d..1e1faa7d4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index f60bb5b65..9dc1b8ba4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 26939accf..448085ef4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index 2d4c44ffe..a4ece79d4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -31,8 +31,8 @@ SOFTWARE. #include #include #include -#include #include +#include #include #ifdef ROS1 #include diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index 864ed05dd..3252644f3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index d515af50c..0f6f63581 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index d41201040..7035f32f8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include -#include #include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index 744127584..6f2486354 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index 91c333e70..8348ad994 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include #include -#include +#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index 7d4dddb2a..dc444b681 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -28,13 +28,13 @@ SOFTWARE. #pragma once #include -#include +#include #include -#include +#include #include +#include #include -#include -#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index 20f78c99c..e76d88fdb 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index bc2ba5339..ee9e4d62b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index 48df981b8..2fc8887d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 53b16d1f1..9ff31cd89 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -30,10 +30,10 @@ SOFTWARE. #include #include #include -#include +#include #include +#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index 222a28475..3f71894cb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index f563edd6a..68b8bd655 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index 4f7a2d6b8..a2e074b3f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index ca064f0f4..f9857a0f5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h index 7e248b153..2ef3f199b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index 36b7aef16..2aaf2d28e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -28,16 +28,16 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include -#include -#include #include #include +#include +#include +#include +#include #include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index 434e00a03..f90a43e05 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -29,9 +29,9 @@ SOFTWARE. #include #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index 4bd4b0a8c..dfdf2a5c7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index 08b2f5acd..95e956aaa 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index 00d71a962..d06368c72 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -28,16 +28,16 @@ SOFTWARE. #pragma once #include -#include -#include #include -#include -#include -#include +#include +#include +#include #include +#include #include -#include -#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index 095f2e3f0..588aeac0a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index d7c5e00be..4acd87379 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -28,9 +28,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index 1f82d2fde..204738acd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include +#include #include -#include #include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index dd3e2be3c..75f1facd4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -28,15 +28,15 @@ SOFTWARE. #pragma once #include -#include -#include +#include +#include #include -#include -#include #include #include -#include -#include +#include +#include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h index 7aab1bcca..e88eb707f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index 101b9f0d9..68f19c330 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 7495ddd84..79c1a5b40 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index 63ba8b0f9..ec8188eef 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include -#include -#include -#include #include #include +#include +#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h index ba15baaf5..836b8e3ae 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index 4478efd76..6ffff2422 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index 72e1b1021..c6a6a4682 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index 4eb00c74a..c8c41c574 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -28,10 +28,10 @@ SOFTWARE. #pragma once #include -#include #include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index 8de410ab9..5aa13769b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -29,14 +29,14 @@ SOFTWARE. #include #include +#include +#include #include -#include #include +#include +#include #include -#include -#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index 7ad7046ea..f6f72682a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -29,8 +29,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index 10963ddb8..39c118f21 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 740dd8665..9c8917e47 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -28,12 +28,12 @@ SOFTWARE. #pragma once #include +#include +#include #include +#include #include -#include #include -#include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 17f5d9abb..3911ecb74 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -30,8 +30,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index 11e153a5d..93c5b423c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index 6bc9a386a..4b569cb76 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -28,8 +28,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; diff --git a/utils/codegen/codegen-rust/rgen/src/conversion/template.rs b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs index 414b48ebe..fa1f23922 100644 --- a/utils/codegen/codegen-rust/rgen/src/conversion/template.rs +++ b/utils/codegen/codegen-rust/rgen/src/conversion/template.rs @@ -69,7 +69,7 @@ pub fn conversion_template( to_ros_members: &str, to_c_members: &str, ) -> String { - let c_includes = includes + let mut c_includes_lines = includes .iter() .map(|member| { if !member.is_primitive { @@ -92,8 +92,9 @@ pub fn conversion_template( }) .collect::>() .into_iter() - .collect::>() - .join("\n"); + .collect::>(); + c_includes_lines.sort(); + let c_includes = c_includes_lines.join("\n"); let ros1_includes = format!( "#include ", pdu = pdu, From 92988ac4fe5ca2cc97c1c8bda89753e9e43197b5 Mon Sep 17 00:00:00 2001 From: Lennart Reiher Date: Fri, 14 Jun 2024 16:22:32 +0200 Subject: [PATCH 20/22] mention rust-based codegen in readme --- README.md | 24 +++++++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 99afbae1b..f1a750c9e 100644 --- a/README.md +++ b/README.md @@ -100,6 +100,16 @@ The ROS message files are auto-generated based on the [ASN.1 definitions](https: -o etsi_its_msgs/etsi_its_cam_msgs/msg ``` +Note that an alternative Rust-based code generation is currently being tested, which might offer better support for more complex message types such as SPATEM/MAPEM or CPM. + +```bash +# etsi_its_messages$ +./utils/codegen/codegen-rust/asn1ToRosMsg.py \ + asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn \ + asn1/raw/cam_en302637_2/cdd/ITS-Container.asn \ + -o etsi_its_msgs/etsi_its_cam_msgs/msg +``` + #### Access Functions Documentation The access functions implemented in the `etsi_its_msgs_utils` package are documented [here](https://ika-rwth-aachen.github.io/etsi_its_messages). @@ -188,14 +198,22 @@ The C++ conversion functions are auto-generated based on the [ASN.1 definitions] -o etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion ``` +Note that an alternative Rust-based code generation is currently being tested, which might offer better support for more complex message types such as SPATEM/MAPEM or CPM. + +```bash +# etsi_its_messages$ +./utils/codegen/codegen-rust/asn1ToConversionHeader.py \ + asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn \ + asn1/raw/cam_en302637_2/cdd/ITS-Container.asn \ + -m cam \ + -o etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion +``` + ## Installation All *etsi_its_messages* packages are released as official ROS / ROS 2 packages and can easily be installed via a package manager. -> [!WARNING] -> The initial release may not have been synced to the package managers yet. In the meantime, please refer to installation from source as shown below. - ```bash sudo apt update sudo apt install ros-$ROS_DISTRO-etsi-its-messages From 7a77cc6cc7e9f753de78ba6593139579335b06a4 Mon Sep 17 00:00:00 2001 From: Jean-Pierre Busch <110477057+jpbusch@users.noreply.github.com> Date: Fri, 14 Jun 2024 15:12:16 +0000 Subject: [PATCH 21/22] align arg parsing py and rust --- .vscode/launch.json | 4 ++-- README.md | 2 +- utils/codegen/codegen-rust/asn1ToConversionHeader.py | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.vscode/launch.json b/.vscode/launch.json index f01f710be..7def9956e 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -124,7 +124,7 @@ "args": [ "asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn", "asn1/raw/cam_en302637_2/cdd/ITS-Container.asn", - "-m", "cam", + "-t", "cam", "-o", "etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion" ], "console": "integratedTerminal", @@ -139,7 +139,7 @@ "args": [ "asn1/raw/denm_en302637_3/DENM-PDU-Descriptions.asn", "asn1/raw/denm_en302637_3/cdd/ITS-Container.asn", - "-m", "denm", + "-t", "denm", "-o", "etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion" ], "console": "integratedTerminal", diff --git a/README.md b/README.md index f1a750c9e..290a13962 100644 --- a/README.md +++ b/README.md @@ -205,7 +205,7 @@ Note that an alternative Rust-based code generation is currently being tested, w ./utils/codegen/codegen-rust/asn1ToConversionHeader.py \ asn1/raw/cam_en302637_2/CAM-PDU-Descriptions.asn \ asn1/raw/cam_en302637_2/cdd/ITS-Container.asn \ - -m cam \ + -t cam \ -o etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion ``` diff --git a/utils/codegen/codegen-rust/asn1ToConversionHeader.py b/utils/codegen/codegen-rust/asn1ToConversionHeader.py index b45fdc690..01abc27a6 100755 --- a/utils/codegen/codegen-rust/asn1ToConversionHeader.py +++ b/utils/codegen/codegen-rust/asn1ToConversionHeader.py @@ -46,7 +46,7 @@ def parseCli(): parser.add_argument("files", type=str, nargs="+", help="ASN1 files") parser.add_argument("-o", "--output-dir", type=str, required=True, help="output directory") parser.add_argument("-td", "--temp-dir", type=str, default=None, help="temporary directory for mounting files to container; uses tempfile by default") - parser.add_argument("-m", "--message", type=str, required=True, help="message name") + parser.add_argument("-t", "--type", type=str, required=True, help="ASN1 type") parser.add_argument("-di", "--docker-image", type=str, default="ghcr.io/ika-rwth-aachen/etsi_its_messages:rgen", help="rgen Docker image") args = parser.parse_args() From 81871405fac1bc5b945fc273b3105f6a0633bd36 Mon Sep 17 00:00:00 2001 From: Jean-Pierre Busch <110477057+jpbusch@users.noreply.github.com> Date: Fri, 14 Jun 2024 15:19:57 +0000 Subject: [PATCH 22/22] for now, regenerate msgs and header files with py-generation --- .../convertAccelerationConfidence.h | 6 +- .../convertAccelerationControl.h | 6 +- .../convertAccidentSubCauseCode.h | 6 +- .../etsi_its_cam_conversion/convertActionID.h | 7 +- ...erseWeatherConditionAdhesionSubCauseCode.h | 6 +- ...itionExtremeWeatherConditionSubCauseCode.h | 6 +- ...eatherConditionPrecipitationSubCauseCode.h | 6 +- ...seWeatherConditionVisibilitySubCauseCode.h | 6 +- .../etsi_its_cam_conversion/convertAltitude.h | 7 +- .../convertAltitudeConfidence.h | 7 +- .../convertAltitudeValue.h | 6 +- .../convertBasicContainer.h | 7 +- ...onvertBasicVehicleContainerHighFrequency.h | 76 +++++++++++------ ...convertBasicVehicleContainerLowFrequency.h | 7 +- .../etsi_its_cam_conversion/convertCAM.h | 7 +- .../convertCamParameters.h | 19 +++-- .../convertCauseCode.h | 5 +- .../convertCauseCodeType.h | 6 +- .../convertCenDsrcTollingZone.h | 14 ++-- .../convertCenDsrcTollingZoneID.h | 7 +- .../convertClosedLanes.h | 29 +++++-- .../convertCollisionRiskSubCauseCode.h | 6 +- .../convertCoopAwareness.h | 7 +- .../convertCurvature.h | 7 +- .../convertCurvatureCalculationMode.h | 7 +- .../convertCurvatureConfidence.h | 7 +- .../convertCurvatureValue.h | 6 +- .../convertDangerousEndOfQueueSubCauseCode.h | 6 +- .../convertDangerousGoodsBasic.h | 7 +- .../convertDangerousGoodsContainer.h | 5 +- .../convertDangerousGoodsExtended.h | 38 +++++---- .../convertDangerousSituationSubCauseCode.h | 6 +- .../convertDeltaAltitude.h | 6 +- .../convertDeltaLatitude.h | 6 +- .../convertDeltaLongitude.h | 6 +- .../convertDeltaReferencePosition.h | 7 +- .../convertDigitalMap.h | 30 ++++--- .../convertDriveDirection.h | 7 +- .../convertDrivingLaneStatus.h | 6 +- .../convertEmbarkationStatus.h | 6 +- .../convertEmergencyContainer.h | 21 +++-- .../convertEmergencyPriority.h | 6 +- ...tEmergencyVehicleApproachingSubCauseCode.h | 6 +- .../convertEnergyStorageType.h | 6 +- .../convertEventHistory.h | 30 ++++--- .../convertEventPoint.h | 14 ++-- .../convertExteriorLights.h | 6 +- .../convertGenerationDeltaTime.h | 6 +- .../convertHardShoulderStatus.h | 7 +- ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 6 +- ...ardousLocationDangerousCurveSubCauseCode.h | 6 +- ...ousLocationObstacleOnTheRoadSubCauseCode.h | 6 +- ...dousLocationSurfaceConditionSubCauseCode.h | 6 +- .../etsi_its_cam_conversion/convertHeading.h | 7 +- .../convertHeadingConfidence.h | 6 +- .../convertHeadingValue.h | 6 +- .../convertHeightLonCarr.h | 6 +- .../convertHighFrequencyContainer.h | 26 +++--- ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 6 +- .../convertHumanProblemSubCauseCode.h | 6 +- .../convertInformationQuality.h | 6 +- .../convertItineraryPath.h | 30 ++++--- .../convertItsPduHeader.h | 7 +- .../convertLanePosition.h | 6 +- .../convertLateralAcceleration.h | 7 +- .../convertLateralAccelerationValue.h | 6 +- .../etsi_its_cam_conversion/convertLatitude.h | 6 +- .../convertLightBarSirenInUse.h | 6 +- .../convertLongitude.h | 6 +- .../convertLongitudinalAcceleration.h | 7 +- .../convertLongitudinalAccelerationValue.h | 6 +- .../convertLowFrequencyContainer.h | 16 ++-- .../convertNumberOfOccupants.h | 6 +- .../convertOpeningDaysHours.h | 6 +- .../convertPathDeltaTime.h | 6 +- .../convertPathHistory.h | 30 ++++--- .../convertPathPoint.h | 12 ++- .../convertPerformanceClass.h | 6 +- .../convertPhoneNumber.h | 6 +- .../convertPosCentMass.h | 6 +- .../convertPosConfidenceEllipse.h | 8 +- .../convertPosFrontAx.h | 6 +- .../convertPosLonCarr.h | 6 +- .../convertPosPillar.h | 6 +- .../convertPositionOfOccupants.h | 6 +- .../convertPositionOfPillars.h | 30 ++++--- .../convertPositioningSolutionType.h | 7 +- .../convertPostCrashSubCauseCode.h | 6 +- .../convertProtectedCommunicationZone.h | 32 ++++--- .../convertProtectedCommunicationZonesRSU.h | 30 ++++--- .../convertProtectedZoneID.h | 6 +- .../convertProtectedZoneRadius.h | 6 +- .../convertProtectedZoneType.h | 7 +- .../convertPtActivation.h | 7 +- .../convertPtActivationData.h | 6 +- .../convertPtActivationType.h | 6 +- .../convertPublicTransportContainer.h | 12 ++- .../convertRSUContainerHighFrequency.h | 12 ++- .../convertReferencePosition.h | 7 +- .../convertRelevanceDistance.h | 7 +- .../convertRelevanceTrafficDirection.h | 7 +- .../convertRequestResponseIndication.h | 7 +- ...cueAndRecoveryWorkInProgressSubCauseCode.h | 6 +- .../convertRescueContainer.h | 5 +- .../convertRestrictedTypes.h | 30 ++++--- .../etsi_its_cam_conversion/convertRoadType.h | 7 +- .../convertRoadWorksContainerBasic.h | 23 +++-- .../convertRoadworksSubCauseCode.h | 6 +- .../convertSafetyCarContainer.h | 30 ++++--- .../convertSemiAxisLength.h | 6 +- .../convertSequenceNumber.h | 6 +- .../convertSignalViolationSubCauseCode.h | 6 +- .../convertSlowVehicleSubCauseCode.h | 6 +- .../convertSpecialTransportContainer.h | 7 +- .../convertSpecialTransportType.h | 6 +- .../convertSpecialVehicleContainer.h | 84 ++++++++++--------- .../etsi_its_cam_conversion/convertSpeed.h | 7 +- .../convertSpeedConfidence.h | 6 +- .../convertSpeedLimit.h | 6 +- .../convertSpeedValue.h | 6 +- .../convertStationID.h | 6 +- .../convertStationType.h | 6 +- .../convertStationarySince.h | 7 +- .../convertStationaryVehicleSubCauseCode.h | 6 +- .../convertSteeringWheelAngle.h | 7 +- .../convertSteeringWheelAngleConfidence.h | 6 +- .../convertSteeringWheelAngleValue.h | 6 +- .../convertSubCauseCodeType.h | 6 +- .../convertTemperature.h | 6 +- .../convertTimestampIts.h | 6 +- .../etsi_its_cam_conversion/convertTraces.h | 30 ++++--- .../convertTrafficConditionSubCauseCode.h | 6 +- .../convertTrafficRule.h | 7 +- .../convertTransmissionInterval.h | 6 +- .../convertTurningRadius.h | 6 +- .../etsi_its_cam_conversion/convertVDS.h | 6 +- .../convertValidityDuration.h | 6 +- .../convertVehicleBreakdownSubCauseCode.h | 6 +- .../convertVehicleIdentification.h | 33 +++++--- .../convertVehicleLength.h | 7 +- ...convertVehicleLengthConfidenceIndication.h | 7 +- .../convertVehicleLengthValue.h | 6 +- .../convertVehicleMass.h | 6 +- .../convertVehicleRole.h | 7 +- .../convertVehicleWidth.h | 6 +- .../convertVerticalAcceleration.h | 7 +- .../convertVerticalAccelerationValue.h | 6 +- .../convertWMInumber.h | 6 +- .../convertWheelBaseVehicle.h | 6 +- .../convertWrongWayDrivingSubCauseCode.h | 6 +- .../etsi_its_cam_conversion/convertYawRate.h | 7 +- .../convertYawRateConfidence.h | 7 +- .../convertYawRateValue.h | 6 +- .../convertAccelerationConfidence.h | 6 +- .../convertAccelerationControl.h | 6 +- .../convertAccidentSubCauseCode.h | 6 +- .../convertActionID.h | 7 +- ...erseWeatherConditionAdhesionSubCauseCode.h | 6 +- ...itionExtremeWeatherConditionSubCauseCode.h | 6 +- ...eatherConditionPrecipitationSubCauseCode.h | 6 +- ...seWeatherConditionVisibilitySubCauseCode.h | 6 +- .../convertAlacarteContainer.h | 53 ++++++++---- .../convertAltitude.h | 7 +- .../convertAltitudeConfidence.h | 7 +- .../convertAltitudeValue.h | 6 +- .../convertCauseCode.h | 5 +- .../convertCauseCodeType.h | 6 +- .../convertCenDsrcTollingZone.h | 14 ++-- .../convertCenDsrcTollingZoneID.h | 7 +- .../convertClosedLanes.h | 29 +++++-- .../convertCollisionRiskSubCauseCode.h | 6 +- .../convertCurvature.h | 7 +- .../convertCurvatureCalculationMode.h | 7 +- .../convertCurvatureConfidence.h | 7 +- .../convertCurvatureValue.h | 6 +- .../etsi_its_denm_conversion/convertDENM.h | 7 +- .../convertDangerousEndOfQueueSubCauseCode.h | 6 +- .../convertDangerousGoodsBasic.h | 7 +- .../convertDangerousGoodsExtended.h | 38 +++++---- .../convertDangerousSituationSubCauseCode.h | 6 +- ...tralizedEnvironmentalNotificationMessage.h | 30 ++++--- .../convertDeltaAltitude.h | 6 +- .../convertDeltaLatitude.h | 6 +- .../convertDeltaLongitude.h | 6 +- .../convertDeltaReferencePosition.h | 7 +- .../convertDigitalMap.h | 30 ++++--- .../convertDriveDirection.h | 7 +- .../convertDrivingLaneStatus.h | 6 +- .../convertEmbarkationStatus.h | 6 +- .../convertEmergencyPriority.h | 6 +- ...tEmergencyVehicleApproachingSubCauseCode.h | 6 +- .../convertEnergyStorageType.h | 6 +- .../convertEventHistory.h | 30 ++++--- .../convertEventPoint.h | 14 ++-- .../convertExteriorLights.h | 6 +- .../convertHardShoulderStatus.h | 7 +- ...rdousLocationAnimalOnTheRoadSubCauseCode.h | 6 +- ...ardousLocationDangerousCurveSubCauseCode.h | 6 +- ...ousLocationObstacleOnTheRoadSubCauseCode.h | 6 +- ...dousLocationSurfaceConditionSubCauseCode.h | 6 +- .../etsi_its_denm_conversion/convertHeading.h | 7 +- .../convertHeadingConfidence.h | 6 +- .../convertHeadingValue.h | 6 +- .../convertHeightLonCarr.h | 6 +- ...onvertHumanPresenceOnTheRoadSubCauseCode.h | 6 +- .../convertHumanProblemSubCauseCode.h | 6 +- .../convertImpactReductionContainer.h | 17 ++-- .../convertInformationQuality.h | 6 +- .../convertItineraryPath.h | 30 ++++--- .../convertItsPduHeader.h | 7 +- .../convertLanePosition.h | 6 +- .../convertLateralAcceleration.h | 7 +- .../convertLateralAccelerationValue.h | 6 +- .../convertLatitude.h | 6 +- .../convertLightBarSirenInUse.h | 6 +- .../convertLocationContainer.h | 30 ++++--- .../convertLongitude.h | 6 +- .../convertLongitudinalAcceleration.h | 7 +- .../convertLongitudinalAccelerationValue.h | 6 +- .../convertManagementContainer.h | 49 +++++++---- .../convertNumberOfOccupants.h | 6 +- .../convertOpeningDaysHours.h | 6 +- .../convertPathDeltaTime.h | 6 +- .../convertPathHistory.h | 30 ++++--- .../convertPathPoint.h | 12 ++- .../convertPerformanceClass.h | 6 +- .../convertPhoneNumber.h | 6 +- .../convertPosCentMass.h | 6 +- .../convertPosConfidenceEllipse.h | 8 +- .../convertPosFrontAx.h | 6 +- .../convertPosLonCarr.h | 6 +- .../convertPosPillar.h | 6 +- .../convertPositionOfOccupants.h | 6 +- .../convertPositionOfPillars.h | 30 ++++--- .../convertPositioningSolutionType.h | 7 +- .../convertPostCrashSubCauseCode.h | 6 +- .../convertProtectedCommunicationZone.h | 32 ++++--- .../convertProtectedCommunicationZonesRSU.h | 30 ++++--- .../convertProtectedZoneID.h | 6 +- .../convertProtectedZoneRadius.h | 6 +- .../convertProtectedZoneType.h | 7 +- .../convertPtActivation.h | 7 +- .../convertPtActivationData.h | 6 +- .../convertPtActivationType.h | 6 +- .../convertReferenceDenms.h | 30 ++++--- .../convertReferencePosition.h | 7 +- .../convertRelevanceDistance.h | 7 +- .../convertRelevanceTrafficDirection.h | 7 +- .../convertRequestResponseIndication.h | 7 +- ...cueAndRecoveryWorkInProgressSubCauseCode.h | 6 +- .../convertRestrictedTypes.h | 30 ++++--- .../convertRoadType.h | 7 +- .../convertRoadWorksContainerExtended.h | 78 +++++++++++------ .../convertRoadworksSubCauseCode.h | 6 +- .../convertSemiAxisLength.h | 6 +- .../convertSequenceNumber.h | 6 +- .../convertSignalViolationSubCauseCode.h | 6 +- .../convertSituationContainer.h | 22 +++-- .../convertSlowVehicleSubCauseCode.h | 6 +- .../convertSpecialTransportType.h | 6 +- .../etsi_its_denm_conversion/convertSpeed.h | 7 +- .../convertSpeedConfidence.h | 6 +- .../convertSpeedLimit.h | 6 +- .../convertSpeedValue.h | 6 +- .../convertStationID.h | 6 +- .../convertStationType.h | 6 +- .../convertStationarySince.h | 7 +- .../convertStationaryVehicleContainer.h | 51 +++++++---- .../convertStationaryVehicleSubCauseCode.h | 6 +- .../convertSteeringWheelAngle.h | 7 +- .../convertSteeringWheelAngleConfidence.h | 6 +- .../convertSteeringWheelAngleValue.h | 6 +- .../convertSubCauseCodeType.h | 6 +- .../convertTemperature.h | 6 +- .../convertTermination.h | 7 +- .../convertTimestampIts.h | 6 +- .../etsi_its_denm_conversion/convertTraces.h | 30 ++++--- .../convertTrafficConditionSubCauseCode.h | 6 +- .../convertTrafficRule.h | 7 +- .../convertTransmissionInterval.h | 6 +- .../convertTurningRadius.h | 6 +- .../etsi_its_denm_conversion/convertVDS.h | 6 +- .../convertValidityDuration.h | 6 +- .../convertVehicleBreakdownSubCauseCode.h | 6 +- .../convertVehicleIdentification.h | 33 +++++--- .../convertVehicleLength.h | 7 +- ...convertVehicleLengthConfidenceIndication.h | 7 +- .../convertVehicleLengthValue.h | 6 +- .../convertVehicleMass.h | 6 +- .../convertVehicleRole.h | 7 +- .../convertVehicleWidth.h | 6 +- .../convertVerticalAcceleration.h | 7 +- .../convertVerticalAccelerationValue.h | 6 +- .../convertWMInumber.h | 6 +- .../convertWheelBaseVehicle.h | 6 +- .../convertWrongWayDrivingSubCauseCode.h | 6 +- .../etsi_its_denm_conversion/convertYawRate.h | 7 +- .../convertYawRateConfidence.h | 7 +- .../convertYawRateValue.h | 6 +- .../msg/AccelerationConfidence.msg | 2 +- .../msg/AccelerationControl.msg | 2 +- .../msg/AccidentSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/ActionID.msg | 2 +- ...seWeatherConditionAdhesionSubCauseCode.msg | 2 +- ...ionExtremeWeatherConditionSubCauseCode.msg | 2 +- ...therConditionPrecipitationSubCauseCode.msg | 2 +- ...WeatherConditionVisibilitySubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/Altitude.msg | 2 +- .../msg/AltitudeConfidence.msg | 1 - .../etsi_its_cam_msgs/msg/AltitudeValue.msg | 2 +- .../etsi_its_cam_msgs/msg/BasicContainer.msg | 2 +- .../BasicVehicleContainerHighFrequency.msg | 2 +- .../msg/BasicVehicleContainerLowFrequency.msg | 2 +- etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg | 2 - .../etsi_its_cam_msgs/msg/CamParameters.msg | 2 +- .../etsi_its_cam_msgs/msg/CauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/CauseCodeType.msg | 2 +- .../msg/CenDsrcTollingZone.msg | 2 +- .../msg/CenDsrcTollingZoneID.msg | 2 +- .../etsi_its_cam_msgs/msg/ClosedLanes.msg | 2 +- .../msg/CollisionRiskSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/CoopAwareness.msg | 2 +- .../etsi_its_cam_msgs/msg/Curvature.msg | 2 +- .../msg/CurvatureCalculationMode.msg | 1 - .../msg/CurvatureConfidence.msg | 1 - .../etsi_its_cam_msgs/msg/CurvatureValue.msg | 2 +- .../msg/DangerousEndOfQueueSubCauseCode.msg | 2 +- .../msg/DangerousGoodsBasic.msg | 1 - .../msg/DangerousGoodsContainer.msg | 2 +- .../msg/DangerousGoodsExtended.msg | 2 +- .../msg/DangerousSituationSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/DeltaAltitude.msg | 2 +- .../etsi_its_cam_msgs/msg/DeltaLatitude.msg | 2 +- .../etsi_its_cam_msgs/msg/DeltaLongitude.msg | 2 +- .../msg/DeltaReferencePosition.msg | 2 +- .../etsi_its_cam_msgs/msg/DigitalMap.msg | 2 +- .../etsi_its_cam_msgs/msg/DriveDirection.msg | 1 - .../msg/DrivingLaneStatus.msg | 1 - .../msg/EmbarkationStatus.msg | 1 - .../msg/EmergencyContainer.msg | 2 +- .../msg/EmergencyPriority.msg | 2 +- ...mergencyVehicleApproachingSubCauseCode.msg | 2 +- .../msg/EnergyStorageType.msg | 2 +- .../etsi_its_cam_msgs/msg/EventHistory.msg | 2 +- .../etsi_its_cam_msgs/msg/EventPoint.msg | 2 +- .../etsi_its_cam_msgs/msg/ExteriorLights.msg | 2 +- .../msg/GenerationDeltaTime.msg | 2 +- .../msg/HardShoulderStatus.msg | 1 - ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 2 +- ...dousLocationDangerousCurveSubCauseCode.msg | 2 +- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 2 +- ...usLocationSurfaceConditionSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/Heading.msg | 2 +- .../msg/HeadingConfidence.msg | 2 +- .../etsi_its_cam_msgs/msg/HeadingValue.msg | 2 +- .../etsi_its_cam_msgs/msg/HeightLonCarr.msg | 2 +- .../msg/HighFrequencyContainer.msg | 2 +- .../HumanPresenceOnTheRoadSubCauseCode.msg | 2 +- .../msg/HumanProblemSubCauseCode.msg | 2 +- .../msg/InformationQuality.msg | 2 +- .../etsi_its_cam_msgs/msg/ItineraryPath.msg | 2 +- .../etsi_its_cam_msgs/msg/ItsPduHeader.msg | 2 +- .../etsi_its_cam_msgs/msg/LanePosition.msg | 2 +- .../msg/LateralAcceleration.msg | 2 +- .../msg/LateralAccelerationValue.msg | 2 +- .../etsi_its_cam_msgs/msg/Latitude.msg | 2 +- .../msg/LightBarSirenInUse.msg | 2 +- .../etsi_its_cam_msgs/msg/Longitude.msg | 2 +- .../msg/LongitudinalAcceleration.msg | 2 +- .../msg/LongitudinalAccelerationValue.msg | 2 +- .../msg/LowFrequencyContainer.msg | 2 +- .../msg/NumberOfOccupants.msg | 2 +- .../msg/OpeningDaysHours.msg | 1 - .../etsi_its_cam_msgs/msg/PathDeltaTime.msg | 10 +-- .../etsi_its_cam_msgs/msg/PathHistory.msg | 2 +- .../etsi_its_cam_msgs/msg/PathPoint.msg | 2 +- .../msg/PerformanceClass.msg | 2 +- .../etsi_its_cam_msgs/msg/PhoneNumber.msg | 2 +- .../etsi_its_cam_msgs/msg/PosCentMass.msg | 2 +- .../msg/PosConfidenceEllipse.msg | 2 +- .../etsi_its_cam_msgs/msg/PosFrontAx.msg | 2 +- .../etsi_its_cam_msgs/msg/PosLonCarr.msg | 2 +- .../etsi_its_cam_msgs/msg/PosPillar.msg | 2 +- .../msg/PositionOfOccupants.msg | 2 +- .../msg/PositionOfPillars.msg | 6 +- .../msg/PositioningSolutionType.msg | 5 +- .../msg/PostCrashSubCauseCode.msg | 2 +- .../msg/ProtectedCommunicationZone.msg | 2 +- .../msg/ProtectedCommunicationZonesRSU.msg | 2 +- .../etsi_its_cam_msgs/msg/ProtectedZoneID.msg | 1 - .../msg/ProtectedZoneRadius.msg | 10 +-- .../msg/ProtectedZoneType.msg | 2 - .../etsi_its_cam_msgs/msg/PtActivation.msg | 2 +- .../msg/PtActivationData.msg | 2 +- .../msg/PtActivationType.msg | 2 +- .../msg/PublicTransportContainer.msg | 2 +- .../msg/RSUContainerHighFrequency.msg | 2 +- .../msg/ReferencePosition.msg | 2 +- .../msg/RelevanceDistance.msg | 1 - .../msg/RelevanceTrafficDirection.msg | 1 - .../msg/RequestResponseIndication.msg | 1 - ...eAndRecoveryWorkInProgressSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/RescueContainer.msg | 2 +- .../etsi_its_cam_msgs/msg/RestrictedTypes.msg | 6 +- .../etsi_its_cam_msgs/msg/RoadType.msg | 1 - .../msg/RoadWorksContainerBasic.msg | 2 +- .../msg/RoadworksSubCauseCode.msg | 2 +- .../msg/SafetyCarContainer.msg | 2 +- .../etsi_its_cam_msgs/msg/SemiAxisLength.msg | 2 +- .../etsi_its_cam_msgs/msg/SequenceNumber.msg | 1 - .../msg/SignalViolationSubCauseCode.msg | 2 +- .../msg/SlowVehicleSubCauseCode.msg | 2 +- .../msg/SpecialTransportContainer.msg | 2 +- .../msg/SpecialTransportType.msg | 2 +- .../msg/SpecialVehicleContainer.msg | 2 +- etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg | 2 +- .../etsi_its_cam_msgs/msg/SpeedConfidence.msg | 2 +- .../etsi_its_cam_msgs/msg/SpeedLimit.msg | 2 +- .../etsi_its_cam_msgs/msg/SpeedValue.msg | 2 +- .../etsi_its_cam_msgs/msg/StationID.msg | 1 - .../etsi_its_cam_msgs/msg/StationType.msg | 2 +- .../etsi_its_cam_msgs/msg/StationarySince.msg | 1 - .../msg/StationaryVehicleSubCauseCode.msg | 2 +- .../msg/SteeringWheelAngle.msg | 2 +- .../msg/SteeringWheelAngleConfidence.msg | 2 +- .../msg/SteeringWheelAngleValue.msg | 2 +- .../msg/SubCauseCodeType.msg | 1 - .../etsi_its_cam_msgs/msg/Temperature.msg | 2 +- .../etsi_its_cam_msgs/msg/TimestampIts.msg | 2 +- .../etsi_its_cam_msgs/msg/Traces.msg | 2 +- .../msg/TrafficConditionSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/TrafficRule.msg | 1 - .../msg/TransmissionInterval.msg | 2 +- .../etsi_its_cam_msgs/msg/TurningRadius.msg | 2 +- etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg | 2 +- .../msg/ValidityDuration.msg | 2 +- .../msg/VehicleBreakdownSubCauseCode.msg | 2 +- .../msg/VehicleIdentification.msg | 10 +-- .../etsi_its_cam_msgs/msg/VehicleLength.msg | 2 +- .../msg/VehicleLengthConfidenceIndication.msg | 1 - .../msg/VehicleLengthValue.msg | 2 +- .../etsi_its_cam_msgs/msg/VehicleMass.msg | 2 +- .../etsi_its_cam_msgs/msg/VehicleRole.msg | 1 - .../etsi_its_cam_msgs/msg/VehicleWidth.msg | 2 +- .../msg/VerticalAcceleration.msg | 2 +- .../msg/VerticalAccelerationValue.msg | 2 +- .../etsi_its_cam_msgs/msg/WMInumber.msg | 2 +- .../msg/WheelBaseVehicle.msg | 2 +- .../msg/WrongWayDrivingSubCauseCode.msg | 2 +- .../etsi_its_cam_msgs/msg/YawRate.msg | 2 +- .../msg/YawRateConfidence.msg | 1 - .../etsi_its_cam_msgs/msg/YawRateValue.msg | 2 +- .../msg/AccelerationConfidence.msg | 2 +- .../msg/AccelerationControl.msg | 2 +- .../msg/AccidentSubCauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/ActionID.msg | 2 +- ...seWeatherConditionAdhesionSubCauseCode.msg | 2 +- ...ionExtremeWeatherConditionSubCauseCode.msg | 2 +- ...therConditionPrecipitationSubCauseCode.msg | 2 +- ...WeatherConditionVisibilitySubCauseCode.msg | 2 +- .../msg/AlacarteContainer.msg | 2 +- .../etsi_its_denm_msgs/msg/Altitude.msg | 2 +- .../msg/AltitudeConfidence.msg | 1 - .../etsi_its_denm_msgs/msg/AltitudeValue.msg | 2 +- .../etsi_its_denm_msgs/msg/CauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/CauseCodeType.msg | 2 +- .../msg/CenDsrcTollingZone.msg | 2 +- .../msg/CenDsrcTollingZoneID.msg | 2 +- .../etsi_its_denm_msgs/msg/ClosedLanes.msg | 2 +- .../msg/CollisionRiskSubCauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/Curvature.msg | 2 +- .../msg/CurvatureCalculationMode.msg | 1 - .../msg/CurvatureConfidence.msg | 1 - .../etsi_its_denm_msgs/msg/CurvatureValue.msg | 2 +- etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg | 2 +- .../msg/DangerousEndOfQueueSubCauseCode.msg | 2 +- .../msg/DangerousGoodsBasic.msg | 1 - .../msg/DangerousGoodsExtended.msg | 2 +- .../msg/DangerousSituationSubCauseCode.msg | 2 +- ...alizedEnvironmentalNotificationMessage.msg | 2 +- .../etsi_its_denm_msgs/msg/DeltaAltitude.msg | 2 +- .../etsi_its_denm_msgs/msg/DeltaLatitude.msg | 2 +- .../etsi_its_denm_msgs/msg/DeltaLongitude.msg | 2 +- .../msg/DeltaReferencePosition.msg | 2 +- .../etsi_its_denm_msgs/msg/DigitalMap.msg | 2 +- .../etsi_its_denm_msgs/msg/DriveDirection.msg | 1 - .../msg/DrivingLaneStatus.msg | 1 - .../msg/EmbarkationStatus.msg | 1 - .../msg/EmergencyPriority.msg | 2 +- ...mergencyVehicleApproachingSubCauseCode.msg | 2 +- .../msg/EnergyStorageType.msg | 2 +- .../etsi_its_denm_msgs/msg/EventHistory.msg | 2 +- .../etsi_its_denm_msgs/msg/EventPoint.msg | 2 +- .../etsi_its_denm_msgs/msg/ExteriorLights.msg | 2 +- .../msg/HardShoulderStatus.msg | 1 - ...ousLocationAnimalOnTheRoadSubCauseCode.msg | 2 +- ...dousLocationDangerousCurveSubCauseCode.msg | 2 +- ...sLocationObstacleOnTheRoadSubCauseCode.msg | 2 +- ...usLocationSurfaceConditionSubCauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/Heading.msg | 2 +- .../msg/HeadingConfidence.msg | 2 +- .../etsi_its_denm_msgs/msg/HeadingValue.msg | 2 +- .../etsi_its_denm_msgs/msg/HeightLonCarr.msg | 2 +- .../HumanPresenceOnTheRoadSubCauseCode.msg | 2 +- .../msg/HumanProblemSubCauseCode.msg | 2 +- .../msg/ImpactReductionContainer.msg | 2 +- .../msg/InformationQuality.msg | 2 +- .../etsi_its_denm_msgs/msg/ItineraryPath.msg | 2 +- .../etsi_its_denm_msgs/msg/ItsPduHeader.msg | 2 +- .../etsi_its_denm_msgs/msg/LanePosition.msg | 2 +- .../msg/LateralAcceleration.msg | 2 +- .../msg/LateralAccelerationValue.msg | 2 +- .../etsi_its_denm_msgs/msg/Latitude.msg | 2 +- .../msg/LightBarSirenInUse.msg | 2 +- .../msg/LocationContainer.msg | 2 +- .../etsi_its_denm_msgs/msg/Longitude.msg | 2 +- .../msg/LongitudinalAcceleration.msg | 2 +- .../msg/LongitudinalAccelerationValue.msg | 2 +- .../msg/ManagementContainer.msg | 5 +- .../msg/NumberOfOccupants.msg | 2 +- .../msg/OpeningDaysHours.msg | 1 - .../etsi_its_denm_msgs/msg/PathDeltaTime.msg | 10 +-- .../etsi_its_denm_msgs/msg/PathHistory.msg | 2 +- .../etsi_its_denm_msgs/msg/PathPoint.msg | 2 +- .../msg/PerformanceClass.msg | 2 +- .../etsi_its_denm_msgs/msg/PhoneNumber.msg | 2 +- .../etsi_its_denm_msgs/msg/PosCentMass.msg | 2 +- .../msg/PosConfidenceEllipse.msg | 2 +- .../etsi_its_denm_msgs/msg/PosFrontAx.msg | 2 +- .../etsi_its_denm_msgs/msg/PosLonCarr.msg | 2 +- .../etsi_its_denm_msgs/msg/PosPillar.msg | 2 +- .../msg/PositionOfOccupants.msg | 2 +- .../msg/PositionOfPillars.msg | 6 +- .../msg/PositioningSolutionType.msg | 5 +- .../msg/PostCrashSubCauseCode.msg | 2 +- .../msg/ProtectedCommunicationZone.msg | 2 +- .../msg/ProtectedCommunicationZonesRSU.msg | 2 +- .../msg/ProtectedZoneID.msg | 1 - .../msg/ProtectedZoneRadius.msg | 10 +-- .../msg/ProtectedZoneType.msg | 2 - .../etsi_its_denm_msgs/msg/PtActivation.msg | 2 +- .../msg/PtActivationData.msg | 2 +- .../msg/PtActivationType.msg | 2 +- .../etsi_its_denm_msgs/msg/ReferenceDenms.msg | 6 +- .../msg/ReferencePosition.msg | 2 +- .../msg/RelevanceDistance.msg | 1 - .../msg/RelevanceTrafficDirection.msg | 1 - .../msg/RequestResponseIndication.msg | 1 - ...eAndRecoveryWorkInProgressSubCauseCode.msg | 2 +- .../msg/RestrictedTypes.msg | 6 +- .../etsi_its_denm_msgs/msg/RoadType.msg | 1 - .../msg/RoadWorksContainerExtended.msg | 2 +- .../msg/RoadworksSubCauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/SemiAxisLength.msg | 2 +- .../etsi_its_denm_msgs/msg/SequenceNumber.msg | 1 - .../msg/SignalViolationSubCauseCode.msg | 2 +- .../msg/SituationContainer.msg | 2 +- .../msg/SlowVehicleSubCauseCode.msg | 2 +- .../msg/SpecialTransportType.msg | 2 +- .../etsi_its_denm_msgs/msg/Speed.msg | 2 +- .../msg/SpeedConfidence.msg | 2 +- .../etsi_its_denm_msgs/msg/SpeedLimit.msg | 2 +- .../etsi_its_denm_msgs/msg/SpeedValue.msg | 2 +- .../etsi_its_denm_msgs/msg/StationID.msg | 1 - .../etsi_its_denm_msgs/msg/StationType.msg | 2 +- .../msg/StationarySince.msg | 1 - .../msg/StationaryVehicleContainer.msg | 2 +- .../msg/StationaryVehicleSubCauseCode.msg | 2 +- .../msg/SteeringWheelAngle.msg | 2 +- .../msg/SteeringWheelAngleConfidence.msg | 2 +- .../msg/SteeringWheelAngleValue.msg | 2 +- .../msg/SubCauseCodeType.msg | 1 - .../etsi_its_denm_msgs/msg/Temperature.msg | 2 +- .../etsi_its_denm_msgs/msg/Termination.msg | 1 - .../etsi_its_denm_msgs/msg/TimestampIts.msg | 2 +- .../etsi_its_denm_msgs/msg/Traces.msg | 2 +- .../msg/TrafficConditionSubCauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/TrafficRule.msg | 1 - .../msg/TransmissionInterval.msg | 2 +- .../etsi_its_denm_msgs/msg/TurningRadius.msg | 2 +- etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg | 2 +- .../msg/ValidityDuration.msg | 2 +- .../msg/VehicleBreakdownSubCauseCode.msg | 2 +- .../msg/VehicleIdentification.msg | 10 +-- .../etsi_its_denm_msgs/msg/VehicleLength.msg | 2 +- .../msg/VehicleLengthConfidenceIndication.msg | 1 - .../msg/VehicleLengthValue.msg | 2 +- .../etsi_its_denm_msgs/msg/VehicleMass.msg | 2 +- .../etsi_its_denm_msgs/msg/VehicleRole.msg | 1 - .../etsi_its_denm_msgs/msg/VehicleWidth.msg | 2 +- .../msg/VerticalAcceleration.msg | 2 +- .../msg/VerticalAccelerationValue.msg | 2 +- .../etsi_its_denm_msgs/msg/WMInumber.msg | 2 +- .../msg/WheelBaseVehicle.msg | 2 +- .../msg/WrongWayDrivingSubCauseCode.msg | 2 +- .../etsi_its_denm_msgs/msg/YawRate.msg | 2 +- .../msg/YawRateConfidence.msg | 1 - .../etsi_its_denm_msgs/msg/YawRateValue.msg | 2 +- 598 files changed, 2034 insertions(+), 1672 deletions(-) diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h index a03db7212..0125b5c14 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AccelerationConfidence(const AccelerationConfidence_t& in, cam_msgs::AccelerationConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccelerationConfidence(const cam_msgs::AccelerationConfidence& in, AccelerationConfidence_t& out) { - memset(&out, 0, sizeof(AccelerationConfidence_t)); + memset(&out, 0, sizeof(AccelerationConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h index c6f025aef..8eecdd8fe 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccelerationControl.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AccelerationControl(const AccelerationControl_t& in, cam_msgs::AccelerationControl& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_AccelerationControl(const cam_msgs::AccelerationControl& in, AccelerationControl_t& out) { - memset(&out, 0, sizeof(AccelerationControl_t)); + memset(&out, 0, sizeof(AccelerationControl_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h index 570a2a065..dd2636450 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAccidentSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AccidentSubCauseCode(const AccidentSubCauseCode_t& in, cam_msgs::AccidentSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccidentSubCauseCode(const cam_msgs::AccidentSubCauseCode& in, AccidentSubCauseCode_t& out) { - memset(&out, 0, sizeof(AccidentSubCauseCode_t)); + memset(&out, 0, sizeof(AccidentSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h index 67d3830ef..8e0c1c721 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertActionID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ActionID(const ActionID_t& in, cam_msgs::ActionID& out) { + toRos_StationID(in.originatingStationID, out.originating_station_id); toRos_SequenceNumber(in.sequenceNumber, out.sequence_number); } void toStruct_ActionID(const cam_msgs::ActionID& in, ActionID_t& out) { + memset(&out, 0, sizeof(ActionID_t)); toStruct_StationID(in.originating_station_id, out.originatingStationID); toStruct_SequenceNumber(in.sequence_number, out.sequenceNumber); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index 9cbc90a7e..9a3f0aaae 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionAdhesionSubCauseCode(const AdverseWeatherCondition_AdhesionSubCauseCode_t& in, cam_msgs::AdverseWeatherConditionAdhesionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionAdhesionSubCauseCode(const cam_msgs::AdverseWeatherConditionAdhesionSubCauseCode& in, AdverseWeatherCondition_AdhesionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_AdhesionSubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_AdhesionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index fc82ff237..28d36aa16 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& in, cam_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const cam_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& in, AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index 572472b91..02d1b6425 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionPrecipitationSubCauseCode(const AdverseWeatherCondition_PrecipitationSubCauseCode_t& in, cam_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionPrecipitationSubCauseCode(const cam_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& in, AdverseWeatherCondition_PrecipitationSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_PrecipitationSubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_PrecipitationSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index c3039da1d..887ceba71 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AdverseWeatherConditionVisibilitySubCauseCode(const AdverseWeatherCondition_VisibilitySubCauseCode_t& in, cam_msgs::AdverseWeatherConditionVisibilitySubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionVisibilitySubCauseCode(const cam_msgs::AdverseWeatherConditionVisibilitySubCauseCode& in, AdverseWeatherCondition_VisibilitySubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_VisibilitySubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_VisibilitySubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h index b97b52246..3cadcf311 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Altitude(const Altitude_t& in, cam_msgs::Altitude& out) { + toRos_AltitudeValue(in.altitudeValue, out.altitude_value); toRos_AltitudeConfidence(in.altitudeConfidence, out.altitude_confidence); } void toStruct_Altitude(const cam_msgs::Altitude& in, Altitude_t& out) { + memset(&out, 0, sizeof(Altitude_t)); toStruct_AltitudeValue(in.altitude_value, out.altitudeValue); toStruct_AltitudeConfidence(in.altitude_confidence, out.altitudeConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h index 20dbdb5d8..1da533614 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AltitudeConfidence(const AltitudeConfidence_t& in, cam_msgs::AltitudeConfidence& out) { + out.value = in; } void toStruct_AltitudeConfidence(const cam_msgs::AltitudeConfidence& in, AltitudeConfidence_t& out) { - memset(&out, 0, sizeof(AltitudeConfidence_t)); + memset(&out, 0, sizeof(AltitudeConfidence_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h index a66df8160..43bd12a66 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertAltitudeValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_AltitudeValue(const AltitudeValue_t& in, cam_msgs::AltitudeValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AltitudeValue(const cam_msgs::AltitudeValue& in, AltitudeValue_t& out) { - memset(&out, 0, sizeof(AltitudeValue_t)); + memset(&out, 0, sizeof(AltitudeValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h index d763f1637..11d2fb702 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_BasicContainer(const BasicContainer_t& in, cam_msgs::BasicContainer& out) { + toRos_StationType(in.stationType, out.station_type); toRos_ReferencePosition(in.referencePosition, out.reference_position); } void toStruct_BasicContainer(const cam_msgs::BasicContainer& in, BasicContainer_t& out) { + memset(&out, 0, sizeof(BasicContainer_t)); toStruct_StationType(in.station_type, out.stationType); toStruct_ReferencePosition(in.reference_position, out.referencePosition); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h index 53f8708c4..3d9247355 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerHighFrequency.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,22 +27,22 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include -#include #include -#include -#include -#include -#include #include -#include +#include #include #include -#include +#include +#include +#include #include +#include +#include +#include +#include +#include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -56,6 +55,7 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_BasicVehicleContainerHighFrequency(const BasicVehicleContainerHighFrequency_t& in, cam_msgs::BasicVehicleContainerHighFrequency& out) { + toRos_Heading(in.heading, out.heading); toRos_Speed(in.speed, out.speed); toRos_DriveDirection(in.driveDirection, out.drive_direction); @@ -69,33 +69,41 @@ void toRos_BasicVehicleContainerHighFrequency(const BasicVehicleContainerHighFre toRos_AccelerationControl(*in.accelerationControl, out.acceleration_control); out.acceleration_control_is_present = true; } + if (in.lanePosition) { toRos_LanePosition(*in.lanePosition, out.lane_position); out.lane_position_is_present = true; } + if (in.steeringWheelAngle) { toRos_SteeringWheelAngle(*in.steeringWheelAngle, out.steering_wheel_angle); out.steering_wheel_angle_is_present = true; } + if (in.lateralAcceleration) { toRos_LateralAcceleration(*in.lateralAcceleration, out.lateral_acceleration); out.lateral_acceleration_is_present = true; } + if (in.verticalAcceleration) { toRos_VerticalAcceleration(*in.verticalAcceleration, out.vertical_acceleration); out.vertical_acceleration_is_present = true; } + if (in.performanceClass) { toRos_PerformanceClass(*in.performanceClass, out.performance_class); out.performance_class_is_present = true; } + if (in.cenDsrcTollingZone) { toRos_CenDsrcTollingZone(*in.cenDsrcTollingZone, out.cen_dsrc_tolling_zone); out.cen_dsrc_tolling_zone_is_present = true; } + } void toStruct_BasicVehicleContainerHighFrequency(const cam_msgs::BasicVehicleContainerHighFrequency& in, BasicVehicleContainerHighFrequency_t& out) { + memset(&out, 0, sizeof(BasicVehicleContainerHighFrequency_t)); toStruct_Heading(in.heading, out.heading); @@ -108,33 +116,47 @@ void toStruct_BasicVehicleContainerHighFrequency(const cam_msgs::BasicVehicleCon toStruct_CurvatureCalculationMode(in.curvature_calculation_mode, out.curvatureCalculationMode); toStruct_YawRate(in.yaw_rate, out.yawRate); if (in.acceleration_control_is_present) { - out.accelerationControl = (AccelerationControl_t*) calloc(1, sizeof(AccelerationControl_t)); - toStruct_AccelerationControl(in.acceleration_control, *out.accelerationControl); + AccelerationControl_t acceleration_control; + toStruct_AccelerationControl(in.acceleration_control, acceleration_control); + out.accelerationControl = new AccelerationControl_t(acceleration_control); } + if (in.lane_position_is_present) { - out.lanePosition = (LanePosition_t*) calloc(1, sizeof(LanePosition_t)); - toStruct_LanePosition(in.lane_position, *out.lanePosition); + LanePosition_t lane_position; + toStruct_LanePosition(in.lane_position, lane_position); + out.lanePosition = new LanePosition_t(lane_position); } + if (in.steering_wheel_angle_is_present) { - out.steeringWheelAngle = (SteeringWheelAngle_t*) calloc(1, sizeof(SteeringWheelAngle_t)); - toStruct_SteeringWheelAngle(in.steering_wheel_angle, *out.steeringWheelAngle); + SteeringWheelAngle_t steering_wheel_angle; + toStruct_SteeringWheelAngle(in.steering_wheel_angle, steering_wheel_angle); + out.steeringWheelAngle = new SteeringWheelAngle_t(steering_wheel_angle); } + if (in.lateral_acceleration_is_present) { - out.lateralAcceleration = (LateralAcceleration_t*) calloc(1, sizeof(LateralAcceleration_t)); - toStruct_LateralAcceleration(in.lateral_acceleration, *out.lateralAcceleration); + LateralAcceleration_t lateral_acceleration; + toStruct_LateralAcceleration(in.lateral_acceleration, lateral_acceleration); + out.lateralAcceleration = new LateralAcceleration_t(lateral_acceleration); } + if (in.vertical_acceleration_is_present) { - out.verticalAcceleration = (VerticalAcceleration_t*) calloc(1, sizeof(VerticalAcceleration_t)); - toStruct_VerticalAcceleration(in.vertical_acceleration, *out.verticalAcceleration); + VerticalAcceleration_t vertical_acceleration; + toStruct_VerticalAcceleration(in.vertical_acceleration, vertical_acceleration); + out.verticalAcceleration = new VerticalAcceleration_t(vertical_acceleration); } + if (in.performance_class_is_present) { - out.performanceClass = (PerformanceClass_t*) calloc(1, sizeof(PerformanceClass_t)); - toStruct_PerformanceClass(in.performance_class, *out.performanceClass); + PerformanceClass_t performance_class; + toStruct_PerformanceClass(in.performance_class, performance_class); + out.performanceClass = new PerformanceClass_t(performance_class); } + if (in.cen_dsrc_tolling_zone_is_present) { - out.cenDsrcTollingZone = (CenDsrcTollingZone_t*) calloc(1, sizeof(CenDsrcTollingZone_t)); - toStruct_CenDsrcTollingZone(in.cen_dsrc_tolling_zone, *out.cenDsrcTollingZone); + CenDsrcTollingZone_t cen_dsrc_tolling_zone; + toStruct_CenDsrcTollingZone(in.cen_dsrc_tolling_zone, cen_dsrc_tolling_zone); + out.cenDsrcTollingZone = new CenDsrcTollingZone_t(cen_dsrc_tolling_zone); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h index 86fa46ef7..b2aff721f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertBasicVehicleContainerLowFrequency.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -43,12 +42,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_BasicVehicleContainerLowFrequency(const BasicVehicleContainerLowFrequency_t& in, cam_msgs::BasicVehicleContainerLowFrequency& out) { + toRos_VehicleRole(in.vehicleRole, out.vehicle_role); toRos_ExteriorLights(in.exteriorLights, out.exterior_lights); toRos_PathHistory(in.pathHistory, out.path_history); } void toStruct_BasicVehicleContainerLowFrequency(const cam_msgs::BasicVehicleContainerLowFrequency& in, BasicVehicleContainerLowFrequency_t& out) { + memset(&out, 0, sizeof(BasicVehicleContainerLowFrequency_t)); toStruct_VehicleRole(in.vehicle_role, out.vehicleRole); @@ -56,4 +57,4 @@ void toStruct_BasicVehicleContainerLowFrequency(const cam_msgs::BasicVehicleCont toStruct_PathHistory(in.path_history, out.pathHistory); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h index eb304dd64..8d5806e82 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCAM.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CAM(const CAM_t& in, cam_msgs::CAM& out) { + toRos_ItsPduHeader(in.header, out.header); toRos_CoopAwareness(in.cam, out.cam); } void toStruct_CAM(const cam_msgs::CAM& in, CAM_t& out) { + memset(&out, 0, sizeof(CAM_t)); toStruct_ItsPduHeader(in.header, out.header); toStruct_CoopAwareness(in.cam, out.cam); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h index 76379d811..39ee0e322 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCamParameters.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -44,31 +43,39 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CamParameters(const CamParameters_t& in, cam_msgs::CamParameters& out) { + toRos_BasicContainer(in.basicContainer, out.basic_container); toRos_HighFrequencyContainer(in.highFrequencyContainer, out.high_frequency_container); if (in.lowFrequencyContainer) { toRos_LowFrequencyContainer(*in.lowFrequencyContainer, out.low_frequency_container); out.low_frequency_container_is_present = true; } + if (in.specialVehicleContainer) { toRos_SpecialVehicleContainer(*in.specialVehicleContainer, out.special_vehicle_container); out.special_vehicle_container_is_present = true; } + } void toStruct_CamParameters(const cam_msgs::CamParameters& in, CamParameters_t& out) { + memset(&out, 0, sizeof(CamParameters_t)); toStruct_BasicContainer(in.basic_container, out.basicContainer); toStruct_HighFrequencyContainer(in.high_frequency_container, out.highFrequencyContainer); if (in.low_frequency_container_is_present) { - out.lowFrequencyContainer = (LowFrequencyContainer_t*) calloc(1, sizeof(LowFrequencyContainer_t)); - toStruct_LowFrequencyContainer(in.low_frequency_container, *out.lowFrequencyContainer); + LowFrequencyContainer_t low_frequency_container; + toStruct_LowFrequencyContainer(in.low_frequency_container, low_frequency_container); + out.lowFrequencyContainer = new LowFrequencyContainer_t(low_frequency_container); } + if (in.special_vehicle_container_is_present) { - out.specialVehicleContainer = (SpecialVehicleContainer_t*) calloc(1, sizeof(SpecialVehicleContainer_t)); - toStruct_SpecialVehicleContainer(in.special_vehicle_container, *out.specialVehicleContainer); + SpecialVehicleContainer_t special_vehicle_container; + toStruct_SpecialVehicleContainer(in.special_vehicle_container, special_vehicle_container); + out.specialVehicleContainer = new SpecialVehicleContainer_t(special_vehicle_container); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h index 99b1c25f0..626031433 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CauseCode(const CauseCode_t& in, cam_msgs::CauseCode& out) { + toRos_CauseCodeType(in.causeCode, out.cause_code); toRos_SubCauseCodeType(in.subCauseCode, out.sub_cause_code); } void toStruct_CauseCode(const cam_msgs::CauseCode& in, CauseCode_t& out) { + memset(&out, 0, sizeof(CauseCode_t)); toStruct_CauseCodeType(in.cause_code, out.causeCode); toStruct_SubCauseCodeType(in.sub_cause_code, out.subCauseCode); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h index ae5d9cdce..7007cb664 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCauseCodeType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CauseCodeType(const CauseCodeType_t& in, cam_msgs::CauseCodeType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CauseCodeType(const cam_msgs::CauseCodeType& in, CauseCodeType_t& out) { - memset(&out, 0, sizeof(CauseCodeType_t)); + memset(&out, 0, sizeof(CauseCodeType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h index 86ca6085b..a715a14e0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZone.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -43,23 +42,28 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CenDsrcTollingZone(const CenDsrcTollingZone_t& in, cam_msgs::CenDsrcTollingZone& out) { + toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.cenDsrcTollingZoneID) { toRos_CenDsrcTollingZoneID(*in.cenDsrcTollingZoneID, out.cen_dsrc_tolling_zone_id); out.cen_dsrc_tolling_zone_id_is_present = true; } + } void toStruct_CenDsrcTollingZone(const cam_msgs::CenDsrcTollingZone& in, CenDsrcTollingZone_t& out) { + memset(&out, 0, sizeof(CenDsrcTollingZone_t)); toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.cen_dsrc_tolling_zone_id_is_present) { - out.cenDsrcTollingZoneID = (CenDsrcTollingZoneID_t*) calloc(1, sizeof(CenDsrcTollingZoneID_t)); - toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, *out.cenDsrcTollingZoneID); + CenDsrcTollingZoneID_t cen_dsrc_tolling_zone_id; + toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, cen_dsrc_tolling_zone_id); + out.cenDsrcTollingZoneID = new CenDsrcTollingZoneID_t(cen_dsrc_tolling_zone_id); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h index a630eb9d3..4b0e2e7d9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCenDsrcTollingZoneID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -37,17 +36,17 @@ namespace cam_msgs = etsi_its_cam_msgs; namespace cam_msgs = etsi_its_cam_msgs::msg; #endif - namespace etsi_its_cam_conversion { void toRos_CenDsrcTollingZoneID(const CenDsrcTollingZoneID_t& in, cam_msgs::CenDsrcTollingZoneID& out) { + toRos_ProtectedZoneID(in, out.value); } void toStruct_CenDsrcTollingZoneID(const cam_msgs::CenDsrcTollingZoneID& in, CenDsrcTollingZoneID_t& out) { - memset(&out, 0, sizeof(CenDsrcTollingZoneID_t)); + memset(&out, 0, sizeof(CenDsrcTollingZoneID_t)); toStruct_ProtectedZoneID(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h index 746e2a208..f6e6aa111 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertClosedLanes.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,9 @@ SOFTWARE. #pragma once #include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,35 +42,46 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ClosedLanes(const ClosedLanes_t& in, cam_msgs::ClosedLanes& out) { + if (in.innerhardShoulderStatus) { toRos_HardShoulderStatus(*in.innerhardShoulderStatus, out.innerhard_shoulder_status); out.innerhard_shoulder_status_is_present = true; } + if (in.outerhardShoulderStatus) { toRos_HardShoulderStatus(*in.outerhardShoulderStatus, out.outerhard_shoulder_status); out.outerhard_shoulder_status_is_present = true; } + if (in.drivingLaneStatus) { toRos_DrivingLaneStatus(*in.drivingLaneStatus, out.driving_lane_status); out.driving_lane_status_is_present = true; } + } void toStruct_ClosedLanes(const cam_msgs::ClosedLanes& in, ClosedLanes_t& out) { + memset(&out, 0, sizeof(ClosedLanes_t)); if (in.innerhard_shoulder_status_is_present) { - out.innerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); - toStruct_HardShoulderStatus(in.innerhard_shoulder_status, *out.innerhardShoulderStatus); + HardShoulderStatus_t innerhard_shoulder_status; + toStruct_HardShoulderStatus(in.innerhard_shoulder_status, innerhard_shoulder_status); + out.innerhardShoulderStatus = new HardShoulderStatus_t(innerhard_shoulder_status); } + if (in.outerhard_shoulder_status_is_present) { - out.outerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); - toStruct_HardShoulderStatus(in.outerhard_shoulder_status, *out.outerhardShoulderStatus); + HardShoulderStatus_t outerhard_shoulder_status; + toStruct_HardShoulderStatus(in.outerhard_shoulder_status, outerhard_shoulder_status); + out.outerhardShoulderStatus = new HardShoulderStatus_t(outerhard_shoulder_status); } + if (in.driving_lane_status_is_present) { - out.drivingLaneStatus = (DrivingLaneStatus_t*) calloc(1, sizeof(DrivingLaneStatus_t)); - toStruct_DrivingLaneStatus(in.driving_lane_status, *out.drivingLaneStatus); + DrivingLaneStatus_t driving_lane_status; + toStruct_DrivingLaneStatus(in.driving_lane_status, driving_lane_status); + out.drivingLaneStatus = new DrivingLaneStatus_t(driving_lane_status); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h index b3cc50334..57d136039 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCollisionRiskSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CollisionRiskSubCauseCode(const CollisionRiskSubCauseCode_t& in, cam_msgs::CollisionRiskSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CollisionRiskSubCauseCode(const cam_msgs::CollisionRiskSubCauseCode& in, CollisionRiskSubCauseCode_t& out) { - memset(&out, 0, sizeof(CollisionRiskSubCauseCode_t)); + memset(&out, 0, sizeof(CollisionRiskSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h index 7882bafdd..ab993b23e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCoopAwareness.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CoopAwareness(const CoopAwareness_t& in, cam_msgs::CoopAwareness& out) { + toRos_GenerationDeltaTime(in.generationDeltaTime, out.generation_delta_time); toRos_CamParameters(in.camParameters, out.cam_parameters); } void toStruct_CoopAwareness(const cam_msgs::CoopAwareness& in, CoopAwareness_t& out) { + memset(&out, 0, sizeof(CoopAwareness_t)); toStruct_GenerationDeltaTime(in.generation_delta_time, out.generationDeltaTime); toStruct_CamParameters(in.cam_parameters, out.camParameters); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h index 07bd550fb..6527951e2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvature.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Curvature(const Curvature_t& in, cam_msgs::Curvature& out) { + toRos_CurvatureValue(in.curvatureValue, out.curvature_value); toRos_CurvatureConfidence(in.curvatureConfidence, out.curvature_confidence); } void toStruct_Curvature(const cam_msgs::Curvature& in, Curvature_t& out) { + memset(&out, 0, sizeof(Curvature_t)); toStruct_CurvatureValue(in.curvature_value, out.curvatureValue); toStruct_CurvatureConfidence(in.curvature_confidence, out.curvatureConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h index 6416aea48..3e9580068 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureCalculationMode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CurvatureCalculationMode(const CurvatureCalculationMode_t& in, cam_msgs::CurvatureCalculationMode& out) { + out.value = in; } void toStruct_CurvatureCalculationMode(const cam_msgs::CurvatureCalculationMode& in, CurvatureCalculationMode_t& out) { - memset(&out, 0, sizeof(CurvatureCalculationMode_t)); + memset(&out, 0, sizeof(CurvatureCalculationMode_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h index 6ea542634..849da3ea5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CurvatureConfidence(const CurvatureConfidence_t& in, cam_msgs::CurvatureConfidence& out) { + out.value = in; } void toStruct_CurvatureConfidence(const cam_msgs::CurvatureConfidence& in, CurvatureConfidence_t& out) { - memset(&out, 0, sizeof(CurvatureConfidence_t)); + memset(&out, 0, sizeof(CurvatureConfidence_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h index b600bef39..da36cf199 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertCurvatureValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_CurvatureValue(const CurvatureValue_t& in, cam_msgs::CurvatureValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CurvatureValue(const cam_msgs::CurvatureValue& in, CurvatureValue_t& out) { - memset(&out, 0, sizeof(CurvatureValue_t)); + memset(&out, 0, sizeof(CurvatureValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h index 168301e6c..1f9239a03 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousEndOfQueueSubCauseCode(const DangerousEndOfQueueSubCauseCode_t& in, cam_msgs::DangerousEndOfQueueSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousEndOfQueueSubCauseCode(const cam_msgs::DangerousEndOfQueueSubCauseCode& in, DangerousEndOfQueueSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousEndOfQueueSubCauseCode_t)); + memset(&out, 0, sizeof(DangerousEndOfQueueSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h index 523746aae..b2571af0d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsBasic.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousGoodsBasic(const DangerousGoodsBasic_t& in, cam_msgs::DangerousGoodsBasic& out) { + out.value = in; } void toStruct_DangerousGoodsBasic(const cam_msgs::DangerousGoodsBasic& in, DangerousGoodsBasic_t& out) { - memset(&out, 0, sizeof(DangerousGoodsBasic_t)); + memset(&out, 0, sizeof(DangerousGoodsBasic_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h index 40ba43d02..1ca5bec78 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -41,13 +40,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousGoodsContainer(const DangerousGoodsContainer_t& in, cam_msgs::DangerousGoodsContainer& out) { + toRos_DangerousGoodsBasic(in.dangerousGoodsBasic, out.dangerous_goods_basic); } void toStruct_DangerousGoodsContainer(const cam_msgs::DangerousGoodsContainer& in, DangerousGoodsContainer_t& out) { + memset(&out, 0, sizeof(DangerousGoodsContainer_t)); toStruct_DangerousGoodsBasic(in.dangerous_goods_basic, out.dangerousGoodsBasic); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h index f4741d2d2..a61abaa25 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousGoodsExtended.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,16 +27,14 @@ SOFTWARE. #pragma once #include -#include +#include +#include +#include +#include #include -#include #include -#include -#include -#include -#include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -50,6 +47,7 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, cam_msgs::DangerousGoodsExtended& out) { + toRos_DangerousGoodsBasic(in.dangerousGoodsType, out.dangerous_goods_type); etsi_its_primitives_conversion::toRos_INTEGER(in.unNumber, out.un_number); etsi_its_primitives_conversion::toRos_BOOLEAN(in.elevatedTemperature, out.elevated_temperature); @@ -59,17 +57,21 @@ void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, cam_msgs:: etsi_its_primitives_conversion::toRos_IA5String(*in.emergencyActionCode, out.emergency_action_code); out.emergency_action_code_is_present = true; } + if (in.phoneNumber) { toRos_PhoneNumber(*in.phoneNumber, out.phone_number); out.phone_number_is_present = true; } + if (in.companyName) { etsi_its_primitives_conversion::toRos_UTF8String(*in.companyName, out.company_name); out.company_name_is_present = true; } + } void toStruct_DangerousGoodsExtended(const cam_msgs::DangerousGoodsExtended& in, DangerousGoodsExtended_t& out) { + memset(&out, 0, sizeof(DangerousGoodsExtended_t)); toStruct_DangerousGoodsBasic(in.dangerous_goods_type, out.dangerousGoodsType); @@ -78,17 +80,23 @@ void toStruct_DangerousGoodsExtended(const cam_msgs::DangerousGoodsExtended& in, etsi_its_primitives_conversion::toStruct_BOOLEAN(in.tunnels_restricted, out.tunnelsRestricted); etsi_its_primitives_conversion::toStruct_BOOLEAN(in.limited_quantity, out.limitedQuantity); if (in.emergency_action_code_is_present) { - out.emergencyActionCode = (IA5String_t*) calloc(1, sizeof(IA5String_t)); - etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, *out.emergencyActionCode); + IA5String_t emergency_action_code; + etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, emergency_action_code); + out.emergencyActionCode = new IA5String_t(emergency_action_code); } + if (in.phone_number_is_present) { - out.phoneNumber = (PhoneNumber_t*) calloc(1, sizeof(PhoneNumber_t)); - toStruct_PhoneNumber(in.phone_number, *out.phoneNumber); + PhoneNumber_t phone_number; + toStruct_PhoneNumber(in.phone_number, phone_number); + out.phoneNumber = new PhoneNumber_t(phone_number); } + if (in.company_name_is_present) { - out.companyName = (UTF8String_t*) calloc(1, sizeof(UTF8String_t)); - etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, *out.companyName); + UTF8String_t company_name; + etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, company_name); + out.companyName = new UTF8String_t(company_name); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h index a60cdcfc7..3efe64189 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDangerousSituationSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DangerousSituationSubCauseCode(const DangerousSituationSubCauseCode_t& in, cam_msgs::DangerousSituationSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousSituationSubCauseCode(const cam_msgs::DangerousSituationSubCauseCode& in, DangerousSituationSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousSituationSubCauseCode_t)); + memset(&out, 0, sizeof(DangerousSituationSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h index 60640d42e..79bc30517 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaAltitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaAltitude(const DeltaAltitude_t& in, cam_msgs::DeltaAltitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaAltitude(const cam_msgs::DeltaAltitude& in, DeltaAltitude_t& out) { - memset(&out, 0, sizeof(DeltaAltitude_t)); + memset(&out, 0, sizeof(DeltaAltitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h index 36371e8af..a0d157e7e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLatitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaLatitude(const DeltaLatitude_t& in, cam_msgs::DeltaLatitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLatitude(const cam_msgs::DeltaLatitude& in, DeltaLatitude_t& out) { - memset(&out, 0, sizeof(DeltaLatitude_t)); + memset(&out, 0, sizeof(DeltaLatitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h index c78a8ddcf..ca6ecb892 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaLongitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaLongitude(const DeltaLongitude_t& in, cam_msgs::DeltaLongitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLongitude(const cam_msgs::DeltaLongitude& in, DeltaLongitude_t& out) { - memset(&out, 0, sizeof(DeltaLongitude_t)); + memset(&out, 0, sizeof(DeltaLongitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h index f67e0be79..ef26422a4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDeltaReferencePosition.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -43,12 +42,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DeltaReferencePosition(const DeltaReferencePosition_t& in, cam_msgs::DeltaReferencePosition& out) { + toRos_DeltaLatitude(in.deltaLatitude, out.delta_latitude); toRos_DeltaLongitude(in.deltaLongitude, out.delta_longitude); toRos_DeltaAltitude(in.deltaAltitude, out.delta_altitude); } void toStruct_DeltaReferencePosition(const cam_msgs::DeltaReferencePosition& in, DeltaReferencePosition_t& out) { + memset(&out, 0, sizeof(DeltaReferencePosition_t)); toStruct_DeltaLatitude(in.delta_latitude, out.deltaLatitude); @@ -56,4 +57,4 @@ void toStruct_DeltaReferencePosition(const cam_msgs::DeltaReferencePosition& in, toStruct_DeltaAltitude(in.delta_altitude, out.deltaAltitude); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h index 7fb57d071..1a1a1cffa 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDigitalMap.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DigitalMap(const DigitalMap_t& in, cam_msgs::DigitalMap& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::ReferencePosition el; - toRos_ReferencePosition(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::ReferencePosition array; + toRos_ReferencePosition(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_DigitalMap(const cam_msgs::DigitalMap& in, DigitalMap_t& out) { + memset(&out, 0, sizeof(DigitalMap_t)); - for (int i = 0; i < in.array.size(); ++i) { - ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); - toStruct_ReferencePosition(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ReferencePosition_t array; + toStruct_ReferencePosition(in.array[i], array); + ReferencePosition_t* array_ptr = new ReferencePosition_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h index a3a9fcb4e..820f45185 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDriveDirection.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DriveDirection(const DriveDirection_t& in, cam_msgs::DriveDirection& out) { + out.value = in; } void toStruct_DriveDirection(const cam_msgs::DriveDirection& in, DriveDirection_t& out) { - memset(&out, 0, sizeof(DriveDirection_t)); + memset(&out, 0, sizeof(DriveDirection_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h index 523b50636..d17439b78 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertDrivingLaneStatus.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_DrivingLaneStatus(const DrivingLaneStatus_t& in, cam_msgs::DrivingLaneStatus& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_DrivingLaneStatus(const cam_msgs::DrivingLaneStatus& in, DrivingLaneStatus_t& out) { - memset(&out, 0, sizeof(DrivingLaneStatus_t)); + memset(&out, 0, sizeof(DrivingLaneStatus_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h index 2081e8643..d60b5b182 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmbarkationStatus.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmbarkationStatus(const EmbarkationStatus_t& in, cam_msgs::EmbarkationStatus& out) { + etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value); } void toStruct_EmbarkationStatus(const cam_msgs::EmbarkationStatus& in, EmbarkationStatus_t& out) { - memset(&out, 0, sizeof(EmbarkationStatus_t)); + memset(&out, 0, sizeof(EmbarkationStatus_t)); etsi_its_primitives_conversion::toStruct_BOOLEAN(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h index c8b08283e..4ef09c64c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -43,29 +42,37 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmergencyContainer(const EmergencyContainer_t& in, cam_msgs::EmergencyContainer& out) { + toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); if (in.incidentIndication) { toRos_CauseCode(*in.incidentIndication, out.incident_indication); out.incident_indication_is_present = true; } + if (in.emergencyPriority) { toRos_EmergencyPriority(*in.emergencyPriority, out.emergency_priority); out.emergency_priority_is_present = true; } + } void toStruct_EmergencyContainer(const cam_msgs::EmergencyContainer& in, EmergencyContainer_t& out) { + memset(&out, 0, sizeof(EmergencyContainer_t)); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); if (in.incident_indication_is_present) { - out.incidentIndication = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); - toStruct_CauseCode(in.incident_indication, *out.incidentIndication); + CauseCode_t incident_indication; + toStruct_CauseCode(in.incident_indication, incident_indication); + out.incidentIndication = new CauseCode_t(incident_indication); } + if (in.emergency_priority_is_present) { - out.emergencyPriority = (EmergencyPriority_t*) calloc(1, sizeof(EmergencyPriority_t)); - toStruct_EmergencyPriority(in.emergency_priority, *out.emergencyPriority); + EmergencyPriority_t emergency_priority; + toStruct_EmergencyPriority(in.emergency_priority, emergency_priority); + out.emergencyPriority = new EmergencyPriority_t(emergency_priority); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h index 151742fcc..17e36a974 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyPriority.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmergencyPriority(const EmergencyPriority_t& in, cam_msgs::EmergencyPriority& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EmergencyPriority(const cam_msgs::EmergencyPriority& in, EmergencyPriority_t& out) { - memset(&out, 0, sizeof(EmergencyPriority_t)); + memset(&out, 0, sizeof(EmergencyPriority_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index f57ac9250..7da6a03d7 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EmergencyVehicleApproachingSubCauseCode(const EmergencyVehicleApproachingSubCauseCode_t& in, cam_msgs::EmergencyVehicleApproachingSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_EmergencyVehicleApproachingSubCauseCode(const cam_msgs::EmergencyVehicleApproachingSubCauseCode& in, EmergencyVehicleApproachingSubCauseCode_t& out) { - memset(&out, 0, sizeof(EmergencyVehicleApproachingSubCauseCode_t)); + memset(&out, 0, sizeof(EmergencyVehicleApproachingSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h index 48bda7f58..b5a00b371 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEnergyStorageType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EnergyStorageType(const EnergyStorageType_t& in, cam_msgs::EnergyStorageType& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EnergyStorageType(const cam_msgs::EnergyStorageType& in, EnergyStorageType_t& out) { - memset(&out, 0, sizeof(EnergyStorageType_t)); + memset(&out, 0, sizeof(EnergyStorageType_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h index 792a45097..4785c8924 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventHistory.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EventHistory(const EventHistory_t& in, cam_msgs::EventHistory& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::EventPoint el; - toRos_EventPoint(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::EventPoint array; + toRos_EventPoint(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_EventHistory(const cam_msgs::EventHistory& in, EventHistory_t& out) { + memset(&out, 0, sizeof(EventHistory_t)); - for (int i = 0; i < in.array.size(); ++i) { - EventPoint_t* el = (EventPoint_t*) calloc(1, sizeof(EventPoint_t)); - toStruct_EventPoint(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + EventPoint_t array; + toStruct_EventPoint(in.array[i], array); + EventPoint_t* array_ptr = new EventPoint_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h index 3b28875d0..c73f053cf 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertEventPoint.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,8 +28,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -43,23 +42,28 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_EventPoint(const EventPoint_t& in, cam_msgs::EventPoint& out) { + toRos_DeltaReferencePosition(in.eventPosition, out.event_position); if (in.eventDeltaTime) { toRos_PathDeltaTime(*in.eventDeltaTime, out.event_delta_time); out.event_delta_time_is_present = true; } + toRos_InformationQuality(in.informationQuality, out.information_quality); } void toStruct_EventPoint(const cam_msgs::EventPoint& in, EventPoint_t& out) { + memset(&out, 0, sizeof(EventPoint_t)); toStruct_DeltaReferencePosition(in.event_position, out.eventPosition); if (in.event_delta_time_is_present) { - out.eventDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); - toStruct_PathDeltaTime(in.event_delta_time, *out.eventDeltaTime); + PathDeltaTime_t event_delta_time; + toStruct_PathDeltaTime(in.event_delta_time, event_delta_time); + out.eventDeltaTime = new PathDeltaTime_t(event_delta_time); } + toStruct_InformationQuality(in.information_quality, out.informationQuality); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h index ab6faf385..923274b83 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertExteriorLights.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ExteriorLights(const ExteriorLights_t& in, cam_msgs::ExteriorLights& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_ExteriorLights(const cam_msgs::ExteriorLights& in, ExteriorLights_t& out) { - memset(&out, 0, sizeof(ExteriorLights_t)); + memset(&out, 0, sizeof(ExteriorLights_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h index d6b8aa77b..41e567351 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertGenerationDeltaTime.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_GenerationDeltaTime(const GenerationDeltaTime_t& in, cam_msgs::GenerationDeltaTime& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_GenerationDeltaTime(const cam_msgs::GenerationDeltaTime& in, GenerationDeltaTime_t& out) { - memset(&out, 0, sizeof(GenerationDeltaTime_t)); + memset(&out, 0, sizeof(GenerationDeltaTime_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h index ced413a5b..d3e97a20c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHardShoulderStatus.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HardShoulderStatus(const HardShoulderStatus_t& in, cam_msgs::HardShoulderStatus& out) { + out.value = in; } void toStruct_HardShoulderStatus(const cam_msgs::HardShoulderStatus& in, HardShoulderStatus_t& out) { - memset(&out, 0, sizeof(HardShoulderStatus_t)); + memset(&out, 0, sizeof(HardShoulderStatus_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 8bd242c16..0e9e4cbe6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationAnimalOnTheRoadSubCauseCode(const HazardousLocation_AnimalOnTheRoadSubCauseCode_t& in, cam_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationAnimalOnTheRoadSubCauseCode(const cam_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& in, HazardousLocation_AnimalOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_AnimalOnTheRoadSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_AnimalOnTheRoadSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index 98d76900e..43b81b7d5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationDangerousCurveSubCauseCode(const HazardousLocation_DangerousCurveSubCauseCode_t& in, cam_msgs::HazardousLocationDangerousCurveSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationDangerousCurveSubCauseCode(const cam_msgs::HazardousLocationDangerousCurveSubCauseCode& in, HazardousLocation_DangerousCurveSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_DangerousCurveSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_DangerousCurveSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index c24b31d49..4e9016370 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationObstacleOnTheRoadSubCauseCode(const HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& in, cam_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationObstacleOnTheRoadSubCauseCode(const cam_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& in, HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_ObstacleOnTheRoadSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_ObstacleOnTheRoadSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index 0b91661b2..8f828c378 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HazardousLocationSurfaceConditionSubCauseCode(const HazardousLocation_SurfaceConditionSubCauseCode_t& in, cam_msgs::HazardousLocationSurfaceConditionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationSurfaceConditionSubCauseCode(const cam_msgs::HazardousLocationSurfaceConditionSubCauseCode& in, HazardousLocation_SurfaceConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_SurfaceConditionSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_SurfaceConditionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h index 0ab06249e..caea1f550 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeading.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Heading(const Heading_t& in, cam_msgs::Heading& out) { + toRos_HeadingValue(in.headingValue, out.heading_value); toRos_HeadingConfidence(in.headingConfidence, out.heading_confidence); } void toStruct_Heading(const cam_msgs::Heading& in, Heading_t& out) { + memset(&out, 0, sizeof(Heading_t)); toStruct_HeadingValue(in.heading_value, out.headingValue); toStruct_HeadingConfidence(in.heading_confidence, out.headingConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h index 2751c0b3e..d5db41c8d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HeadingConfidence(const HeadingConfidence_t& in, cam_msgs::HeadingConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingConfidence(const cam_msgs::HeadingConfidence& in, HeadingConfidence_t& out) { - memset(&out, 0, sizeof(HeadingConfidence_t)); + memset(&out, 0, sizeof(HeadingConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h index eaaeef13b..06e9b1054 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeadingValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HeadingValue(const HeadingValue_t& in, cam_msgs::HeadingValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingValue(const cam_msgs::HeadingValue& in, HeadingValue_t& out) { - memset(&out, 0, sizeof(HeadingValue_t)); + memset(&out, 0, sizeof(HeadingValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h index 018e67279..a0f89ca1d 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHeightLonCarr.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HeightLonCarr(const HeightLonCarr_t& in, cam_msgs::HeightLonCarr& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeightLonCarr(const cam_msgs::HeightLonCarr& in, HeightLonCarr_t& out) { - memset(&out, 0, sizeof(HeightLonCarr_t)); + memset(&out, 0, sizeof(HeightLonCarr_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h index 1544cc1d2..9a942860a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHighFrequencyContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,33 +41,32 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HighFrequencyContainer(const HighFrequencyContainer_t& in, cam_msgs::HighFrequencyContainer& out) { - switch (in.present) { - case HighFrequencyContainer_PR_basicVehicleContainerHighFrequency: + + if (in.present == HighFrequencyContainer_PR::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency) { toRos_BasicVehicleContainerHighFrequency(in.choice.basicVehicleContainerHighFrequency, out.basic_vehicle_container_high_frequency); out.choice = cam_msgs::HighFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY; - break; - case HighFrequencyContainer_PR_rsuContainerHighFrequency: + } + + if (in.present == HighFrequencyContainer_PR::HighFrequencyContainer_PR_rsuContainerHighFrequency) { toRos_RSUContainerHighFrequency(in.choice.rsuContainerHighFrequency, out.rsu_container_high_frequency); out.choice = cam_msgs::HighFrequencyContainer::CHOICE_RSU_CONTAINER_HIGH_FREQUENCY; - break; - default: break; } } void toStruct_HighFrequencyContainer(const cam_msgs::HighFrequencyContainer& in, HighFrequencyContainer_t& out) { + memset(&out, 0, sizeof(HighFrequencyContainer_t)); - switch (in.choice) { - case cam_msgs::HighFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY: + if (in.choice == cam_msgs::HighFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_HIGH_FREQUENCY) { toStruct_BasicVehicleContainerHighFrequency(in.basic_vehicle_container_high_frequency, out.choice.basicVehicleContainerHighFrequency); out.present = HighFrequencyContainer_PR::HighFrequencyContainer_PR_basicVehicleContainerHighFrequency; - break; - case cam_msgs::HighFrequencyContainer::CHOICE_RSU_CONTAINER_HIGH_FREQUENCY: + } + + if (in.choice == cam_msgs::HighFrequencyContainer::CHOICE_RSU_CONTAINER_HIGH_FREQUENCY) { toStruct_RSUContainerHighFrequency(in.rsu_container_high_frequency, out.choice.rsuContainerHighFrequency); out.present = HighFrequencyContainer_PR::HighFrequencyContainer_PR_rsuContainerHighFrequency; - break; - default: break; } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index 15bfc07e0..3a223f984 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HumanPresenceOnTheRoadSubCauseCode(const HumanPresenceOnTheRoadSubCauseCode_t& in, cam_msgs::HumanPresenceOnTheRoadSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanPresenceOnTheRoadSubCauseCode(const cam_msgs::HumanPresenceOnTheRoadSubCauseCode& in, HumanPresenceOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanPresenceOnTheRoadSubCauseCode_t)); + memset(&out, 0, sizeof(HumanPresenceOnTheRoadSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h index 19c72f33f..d97aaa8c8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertHumanProblemSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_HumanProblemSubCauseCode(const HumanProblemSubCauseCode_t& in, cam_msgs::HumanProblemSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanProblemSubCauseCode(const cam_msgs::HumanProblemSubCauseCode& in, HumanProblemSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanProblemSubCauseCode_t)); + memset(&out, 0, sizeof(HumanProblemSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h index 25f05724e..744fadf76 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertInformationQuality.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_InformationQuality(const InformationQuality_t& in, cam_msgs::InformationQuality& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_InformationQuality(const cam_msgs::InformationQuality& in, InformationQuality_t& out) { - memset(&out, 0, sizeof(InformationQuality_t)); + memset(&out, 0, sizeof(InformationQuality_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h index c30af34f9..d63d0779a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItineraryPath.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ItineraryPath(const ItineraryPath_t& in, cam_msgs::ItineraryPath& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::ReferencePosition el; - toRos_ReferencePosition(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::ReferencePosition array; + toRos_ReferencePosition(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_ItineraryPath(const cam_msgs::ItineraryPath& in, ItineraryPath_t& out) { + memset(&out, 0, sizeof(ItineraryPath_t)); - for (int i = 0; i < in.array.size(); ++i) { - ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); - toStruct_ReferencePosition(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ReferencePosition_t array; + toStruct_ReferencePosition(in.array[i], array); + ReferencePosition_t* array_ptr = new ReferencePosition_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h index f8ff33e30..22bc2dbcc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertItsPduHeader.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,7 @@ SOFTWARE. #pragma once #include -#include +#include #include #include #ifdef ROS1 @@ -43,12 +42,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ItsPduHeader(const ItsPduHeader_t& in, cam_msgs::ItsPduHeader& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in.protocolVersion, out.protocol_version); etsi_its_primitives_conversion::toRos_INTEGER(in.messageID, out.message_id); toRos_StationID(in.stationID, out.station_id); } void toStruct_ItsPduHeader(const cam_msgs::ItsPduHeader& in, ItsPduHeader_t& out) { + memset(&out, 0, sizeof(ItsPduHeader_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.protocol_version, out.protocolVersion); @@ -56,4 +57,4 @@ void toStruct_ItsPduHeader(const cam_msgs::ItsPduHeader& in, ItsPduHeader_t& out toStruct_StationID(in.station_id, out.stationID); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h index 76d7ce03f..a91fd72d3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLanePosition.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LanePosition(const LanePosition_t& in, cam_msgs::LanePosition& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LanePosition(const cam_msgs::LanePosition& in, LanePosition_t& out) { - memset(&out, 0, sizeof(LanePosition_t)); + memset(&out, 0, sizeof(LanePosition_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h index 0562c2682..e6ffd03f5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAcceleration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LateralAcceleration(const LateralAcceleration_t& in, cam_msgs::LateralAcceleration& out) { + toRos_LateralAccelerationValue(in.lateralAccelerationValue, out.lateral_acceleration_value); toRos_AccelerationConfidence(in.lateralAccelerationConfidence, out.lateral_acceleration_confidence); } void toStruct_LateralAcceleration(const cam_msgs::LateralAcceleration& in, LateralAcceleration_t& out) { + memset(&out, 0, sizeof(LateralAcceleration_t)); toStruct_LateralAccelerationValue(in.lateral_acceleration_value, out.lateralAccelerationValue); toStruct_AccelerationConfidence(in.lateral_acceleration_confidence, out.lateralAccelerationConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h index 0c1e76a3d..c344993a9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLateralAccelerationValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LateralAccelerationValue(const LateralAccelerationValue_t& in, cam_msgs::LateralAccelerationValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LateralAccelerationValue(const cam_msgs::LateralAccelerationValue& in, LateralAccelerationValue_t& out) { - memset(&out, 0, sizeof(LateralAccelerationValue_t)); + memset(&out, 0, sizeof(LateralAccelerationValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h index 378fde951..ab91dcc1b 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLatitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Latitude(const Latitude_t& in, cam_msgs::Latitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Latitude(const cam_msgs::Latitude& in, Latitude_t& out) { - memset(&out, 0, sizeof(Latitude_t)); + memset(&out, 0, sizeof(Latitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h index 99b0e1109..c4d0682e9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLightBarSirenInUse.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LightBarSirenInUse(const LightBarSirenInUse_t& in, cam_msgs::LightBarSirenInUse& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_LightBarSirenInUse(const cam_msgs::LightBarSirenInUse& in, LightBarSirenInUse_t& out) { - memset(&out, 0, sizeof(LightBarSirenInUse_t)); + memset(&out, 0, sizeof(LightBarSirenInUse_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h index 816b730e6..6caf589b0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Longitude(const Longitude_t& in, cam_msgs::Longitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Longitude(const cam_msgs::Longitude& in, Longitude_t& out) { - memset(&out, 0, sizeof(Longitude_t)); + memset(&out, 0, sizeof(Longitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h index e2fe9ede9..6bba1a608 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAcceleration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LongitudinalAcceleration(const LongitudinalAcceleration_t& in, cam_msgs::LongitudinalAcceleration& out) { + toRos_LongitudinalAccelerationValue(in.longitudinalAccelerationValue, out.longitudinal_acceleration_value); toRos_AccelerationConfidence(in.longitudinalAccelerationConfidence, out.longitudinal_acceleration_confidence); } void toStruct_LongitudinalAcceleration(const cam_msgs::LongitudinalAcceleration& in, LongitudinalAcceleration_t& out) { + memset(&out, 0, sizeof(LongitudinalAcceleration_t)); toStruct_LongitudinalAccelerationValue(in.longitudinal_acceleration_value, out.longitudinalAccelerationValue); toStruct_AccelerationConfidence(in.longitudinal_acceleration_confidence, out.longitudinalAccelerationConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h index 1392c8e74..1af7724de 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLongitudinalAccelerationValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LongitudinalAccelerationValue(const LongitudinalAccelerationValue_t& in, cam_msgs::LongitudinalAccelerationValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LongitudinalAccelerationValue(const cam_msgs::LongitudinalAccelerationValue& in, LongitudinalAccelerationValue_t& out) { - memset(&out, 0, sizeof(LongitudinalAccelerationValue_t)); + memset(&out, 0, sizeof(LongitudinalAccelerationValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h index 31e624392..4f9586ed1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertLowFrequencyContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -41,25 +40,22 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_LowFrequencyContainer(const LowFrequencyContainer_t& in, cam_msgs::LowFrequencyContainer& out) { - switch (in.present) { - case LowFrequencyContainer_PR_basicVehicleContainerLowFrequency: + + if (in.present == LowFrequencyContainer_PR::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency) { toRos_BasicVehicleContainerLowFrequency(in.choice.basicVehicleContainerLowFrequency, out.basic_vehicle_container_low_frequency); out.choice = cam_msgs::LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY; - break; - default: break; } } void toStruct_LowFrequencyContainer(const cam_msgs::LowFrequencyContainer& in, LowFrequencyContainer_t& out) { + memset(&out, 0, sizeof(LowFrequencyContainer_t)); - switch (in.choice) { - case cam_msgs::LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY: + if (in.choice == cam_msgs::LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY) { toStruct_BasicVehicleContainerLowFrequency(in.basic_vehicle_container_low_frequency, out.choice.basicVehicleContainerLowFrequency); out.present = LowFrequencyContainer_PR::LowFrequencyContainer_PR_basicVehicleContainerLowFrequency; - break; - default: break; } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h index 5e3e2f797..d8c0a6dea 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertNumberOfOccupants.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_NumberOfOccupants(const NumberOfOccupants_t& in, cam_msgs::NumberOfOccupants& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_NumberOfOccupants(const cam_msgs::NumberOfOccupants& in, NumberOfOccupants_t& out) { - memset(&out, 0, sizeof(NumberOfOccupants_t)); + memset(&out, 0, sizeof(NumberOfOccupants_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h index 06b61866d..d3abe0aec 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertOpeningDaysHours.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_OpeningDaysHours(const OpeningDaysHours_t& in, cam_msgs::OpeningDaysHours& out) { + etsi_its_primitives_conversion::toRos_UTF8String(in, out.value); } void toStruct_OpeningDaysHours(const cam_msgs::OpeningDaysHours& in, OpeningDaysHours_t& out) { - memset(&out, 0, sizeof(OpeningDaysHours_t)); + memset(&out, 0, sizeof(OpeningDaysHours_t)); etsi_its_primitives_conversion::toStruct_UTF8String(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h index a8c1c3400..4093721f0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathDeltaTime.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PathDeltaTime(const PathDeltaTime_t& in, cam_msgs::PathDeltaTime& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PathDeltaTime(const cam_msgs::PathDeltaTime& in, PathDeltaTime_t& out) { - memset(&out, 0, sizeof(PathDeltaTime_t)); + memset(&out, 0, sizeof(PathDeltaTime_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h index d043a9530..bfe8ec960 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathHistory.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PathHistory(const PathHistory_t& in, cam_msgs::PathHistory& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::PathPoint el; - toRos_PathPoint(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::PathPoint array; + toRos_PathPoint(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_PathHistory(const cam_msgs::PathHistory& in, PathHistory_t& out) { + memset(&out, 0, sizeof(PathHistory_t)); - for (int i = 0; i < in.array.size(); ++i) { - PathPoint_t* el = (PathPoint_t*) calloc(1, sizeof(PathPoint_t)); - toStruct_PathPoint(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + PathPoint_t array; + toStruct_PathPoint(in.array[i], array); + PathPoint_t* array_ptr = new PathPoint_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h index 1e1faa7d4..f81dd2571 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPathPoint.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,21 +41,26 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PathPoint(const PathPoint_t& in, cam_msgs::PathPoint& out) { + toRos_DeltaReferencePosition(in.pathPosition, out.path_position); if (in.pathDeltaTime) { toRos_PathDeltaTime(*in.pathDeltaTime, out.path_delta_time); out.path_delta_time_is_present = true; } + } void toStruct_PathPoint(const cam_msgs::PathPoint& in, PathPoint_t& out) { + memset(&out, 0, sizeof(PathPoint_t)); toStruct_DeltaReferencePosition(in.path_position, out.pathPosition); if (in.path_delta_time_is_present) { - out.pathDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); - toStruct_PathDeltaTime(in.path_delta_time, *out.pathDeltaTime); + PathDeltaTime_t path_delta_time; + toStruct_PathDeltaTime(in.path_delta_time, path_delta_time); + out.pathDeltaTime = new PathDeltaTime_t(path_delta_time); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h index 4247a000f..02e164d52 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPerformanceClass.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PerformanceClass(const PerformanceClass_t& in, cam_msgs::PerformanceClass& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PerformanceClass(const cam_msgs::PerformanceClass& in, PerformanceClass_t& out) { - memset(&out, 0, sizeof(PerformanceClass_t)); + memset(&out, 0, sizeof(PerformanceClass_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h index 1ac9fffec..47287baac 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPhoneNumber.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PhoneNumber(const PhoneNumber_t& in, cam_msgs::PhoneNumber& out) { + etsi_its_primitives_conversion::toRos_NumericString(in, out.value); } void toStruct_PhoneNumber(const cam_msgs::PhoneNumber& in, PhoneNumber_t& out) { - memset(&out, 0, sizeof(PhoneNumber_t)); + memset(&out, 0, sizeof(PhoneNumber_t)); etsi_its_primitives_conversion::toStruct_NumericString(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h index 261089db7..634095c68 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosCentMass.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosCentMass(const PosCentMass_t& in, cam_msgs::PosCentMass& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosCentMass(const cam_msgs::PosCentMass& in, PosCentMass_t& out) { - memset(&out, 0, sizeof(PosCentMass_t)); + memset(&out, 0, sizeof(PosCentMass_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h index 9dc1b8ba4..beae50a76 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosConfidenceEllipse.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,9 @@ SOFTWARE. #pragma once #include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,12 +42,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosConfidenceEllipse(const PosConfidenceEllipse_t& in, cam_msgs::PosConfidenceEllipse& out) { + toRos_SemiAxisLength(in.semiMajorConfidence, out.semi_major_confidence); toRos_SemiAxisLength(in.semiMinorConfidence, out.semi_minor_confidence); toRos_HeadingValue(in.semiMajorOrientation, out.semi_major_orientation); } void toStruct_PosConfidenceEllipse(const cam_msgs::PosConfidenceEllipse& in, PosConfidenceEllipse_t& out) { + memset(&out, 0, sizeof(PosConfidenceEllipse_t)); toStruct_SemiAxisLength(in.semi_major_confidence, out.semiMajorConfidence); @@ -55,4 +57,4 @@ void toStruct_PosConfidenceEllipse(const cam_msgs::PosConfidenceEllipse& in, Pos toStruct_HeadingValue(in.semi_major_orientation, out.semiMajorOrientation); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h index c058cfcd1..f93562bc5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosFrontAx.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosFrontAx(const PosFrontAx_t& in, cam_msgs::PosFrontAx& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosFrontAx(const cam_msgs::PosFrontAx& in, PosFrontAx_t& out) { - memset(&out, 0, sizeof(PosFrontAx_t)); + memset(&out, 0, sizeof(PosFrontAx_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h index 7d127fe22..fba545286 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosLonCarr.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosLonCarr(const PosLonCarr_t& in, cam_msgs::PosLonCarr& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosLonCarr(const cam_msgs::PosLonCarr& in, PosLonCarr_t& out) { - memset(&out, 0, sizeof(PosLonCarr_t)); + memset(&out, 0, sizeof(PosLonCarr_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h index 71a5c95bf..665595029 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPosPillar.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PosPillar(const PosPillar_t& in, cam_msgs::PosPillar& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosPillar(const cam_msgs::PosPillar& in, PosPillar_t& out) { - memset(&out, 0, sizeof(PosPillar_t)); + memset(&out, 0, sizeof(PosPillar_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h index 0764a8a2d..9c58fea75 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfOccupants.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PositionOfOccupants(const PositionOfOccupants_t& in, cam_msgs::PositionOfOccupants& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_PositionOfOccupants(const cam_msgs::PositionOfOccupants& in, PositionOfOccupants_t& out) { - memset(&out, 0, sizeof(PositionOfOccupants_t)); + memset(&out, 0, sizeof(PositionOfOccupants_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h index 448085ef4..9180d5e55 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositionOfPillars.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PositionOfPillars(const PositionOfPillars_t& in, cam_msgs::PositionOfPillars& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::PosPillar el; - toRos_PosPillar(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::PosPillar array; + toRos_PosPillar(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_PositionOfPillars(const cam_msgs::PositionOfPillars& in, PositionOfPillars_t& out) { + memset(&out, 0, sizeof(PositionOfPillars_t)); - for (int i = 0; i < in.array.size(); ++i) { - PosPillar_t* el = (PosPillar_t*) calloc(1, sizeof(PosPillar_t)); - toStruct_PosPillar(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + PosPillar_t array; + toStruct_PosPillar(in.array[i], array); + PosPillar_t* array_ptr = new PosPillar_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h index ea54fae60..9161dae3c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPositioningSolutionType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PositioningSolutionType(const PositioningSolutionType_t& in, cam_msgs::PositioningSolutionType& out) { + out.value = in; } void toStruct_PositioningSolutionType(const cam_msgs::PositioningSolutionType& in, PositioningSolutionType_t& out) { - memset(&out, 0, sizeof(PositioningSolutionType_t)); + memset(&out, 0, sizeof(PositioningSolutionType_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h index aef888ec9..872638dfc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPostCrashSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PostCrashSubCauseCode(const PostCrashSubCauseCode_t& in, cam_msgs::PostCrashSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PostCrashSubCauseCode(const cam_msgs::PostCrashSubCauseCode& in, PostCrashSubCauseCode_t& out) { - memset(&out, 0, sizeof(PostCrashSubCauseCode_t)); + memset(&out, 0, sizeof(PostCrashSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h index a4ece79d4..2fffe65b6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZone.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,12 +27,12 @@ SOFTWARE. #pragma once #include +#include +#include #include #include -#include #include -#include -#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -46,41 +45,52 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedCommunicationZone(const ProtectedCommunicationZone_t& in, cam_msgs::ProtectedCommunicationZone& out) { + toRos_ProtectedZoneType(in.protectedZoneType, out.protected_zone_type); if (in.expiryTime) { toRos_TimestampIts(*in.expiryTime, out.expiry_time); out.expiry_time_is_present = true; } + toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.protectedZoneRadius) { toRos_ProtectedZoneRadius(*in.protectedZoneRadius, out.protected_zone_radius); out.protected_zone_radius_is_present = true; } + if (in.protectedZoneID) { toRos_ProtectedZoneID(*in.protectedZoneID, out.protected_zone_id); out.protected_zone_id_is_present = true; } + } void toStruct_ProtectedCommunicationZone(const cam_msgs::ProtectedCommunicationZone& in, ProtectedCommunicationZone_t& out) { + memset(&out, 0, sizeof(ProtectedCommunicationZone_t)); toStruct_ProtectedZoneType(in.protected_zone_type, out.protectedZoneType); if (in.expiry_time_is_present) { - out.expiryTime = (TimestampIts_t*) calloc(1, sizeof(TimestampIts_t)); - toStruct_TimestampIts(in.expiry_time, *out.expiryTime); + TimestampIts_t expiry_time; + toStruct_TimestampIts(in.expiry_time, expiry_time); + out.expiryTime = new TimestampIts_t(expiry_time); } + toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.protected_zone_radius_is_present) { - out.protectedZoneRadius = (ProtectedZoneRadius_t*) calloc(1, sizeof(ProtectedZoneRadius_t)); - toStruct_ProtectedZoneRadius(in.protected_zone_radius, *out.protectedZoneRadius); + ProtectedZoneRadius_t protected_zone_radius; + toStruct_ProtectedZoneRadius(in.protected_zone_radius, protected_zone_radius); + out.protectedZoneRadius = new ProtectedZoneRadius_t(protected_zone_radius); } + if (in.protected_zone_id_is_present) { - out.protectedZoneID = (ProtectedZoneID_t*) calloc(1, sizeof(ProtectedZoneID_t)); - toStruct_ProtectedZoneID(in.protected_zone_id, *out.protectedZoneID); + ProtectedZoneID_t protected_zone_id; + toStruct_ProtectedZoneID(in.protected_zone_id, protected_zone_id); + out.protectedZoneID = new ProtectedZoneID_t(protected_zone_id); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h index 3252644f3..69d223925 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedCommunicationZonesRSU.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedCommunicationZonesRSU(const ProtectedCommunicationZonesRSU_t& in, cam_msgs::ProtectedCommunicationZonesRSU& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::ProtectedCommunicationZone el; - toRos_ProtectedCommunicationZone(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::ProtectedCommunicationZone array; + toRos_ProtectedCommunicationZone(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_ProtectedCommunicationZonesRSU(const cam_msgs::ProtectedCommunicationZonesRSU& in, ProtectedCommunicationZonesRSU_t& out) { + memset(&out, 0, sizeof(ProtectedCommunicationZonesRSU_t)); - for (int i = 0; i < in.array.size(); ++i) { - ProtectedCommunicationZone_t* el = (ProtectedCommunicationZone_t*) calloc(1, sizeof(ProtectedCommunicationZone_t)); - toStruct_ProtectedCommunicationZone(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ProtectedCommunicationZone_t array; + toStruct_ProtectedCommunicationZone(in.array[i], array); + ProtectedCommunicationZone_t* array_ptr = new ProtectedCommunicationZone_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h index eaf9ef65f..b675234a2 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedZoneID(const ProtectedZoneID_t& in, cam_msgs::ProtectedZoneID& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneID(const cam_msgs::ProtectedZoneID& in, ProtectedZoneID_t& out) { - memset(&out, 0, sizeof(ProtectedZoneID_t)); + memset(&out, 0, sizeof(ProtectedZoneID_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h index 2852508ee..a385b10fc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneRadius.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedZoneRadius(const ProtectedZoneRadius_t& in, cam_msgs::ProtectedZoneRadius& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneRadius(const cam_msgs::ProtectedZoneRadius& in, ProtectedZoneRadius_t& out) { - memset(&out, 0, sizeof(ProtectedZoneRadius_t)); + memset(&out, 0, sizeof(ProtectedZoneRadius_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h index 327d7709b..71fda1286 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertProtectedZoneType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ProtectedZoneType(const ProtectedZoneType_t& in, cam_msgs::ProtectedZoneType& out) { + out.value = in; } void toStruct_ProtectedZoneType(const cam_msgs::ProtectedZoneType& in, ProtectedZoneType_t& out) { - memset(&out, 0, sizeof(ProtectedZoneType_t)); + memset(&out, 0, sizeof(ProtectedZoneType_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h index 0f6f63581..25cbe5eb8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivation.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PtActivation(const PtActivation_t& in, cam_msgs::PtActivation& out) { + toRos_PtActivationType(in.ptActivationType, out.pt_activation_type); toRos_PtActivationData(in.ptActivationData, out.pt_activation_data); } void toStruct_PtActivation(const cam_msgs::PtActivation& in, PtActivation_t& out) { + memset(&out, 0, sizeof(PtActivation_t)); toStruct_PtActivationType(in.pt_activation_type, out.ptActivationType); toStruct_PtActivationData(in.pt_activation_data, out.ptActivationData); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h index 40920b99f..11588d133 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationData.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PtActivationData(const PtActivationData_t& in, cam_msgs::PtActivationData& out) { + etsi_its_primitives_conversion::toRos_OCTET_STRING(in, out.value); } void toStruct_PtActivationData(const cam_msgs::PtActivationData& in, PtActivationData_t& out) { - memset(&out, 0, sizeof(PtActivationData_t)); + memset(&out, 0, sizeof(PtActivationData_t)); etsi_its_primitives_conversion::toStruct_OCTET_STRING(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h index cef85430e..68d09fae1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPtActivationType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PtActivationType(const PtActivationType_t& in, cam_msgs::PtActivationType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PtActivationType(const cam_msgs::PtActivationType& in, PtActivationType_t& out) { - memset(&out, 0, sizeof(PtActivationType_t)); + memset(&out, 0, sizeof(PtActivationType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h index 613539d55..c06b93080 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertPublicTransportContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,21 +41,26 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_PublicTransportContainer(const PublicTransportContainer_t& in, cam_msgs::PublicTransportContainer& out) { + toRos_EmbarkationStatus(in.embarkationStatus, out.embarkation_status); if (in.ptActivation) { toRos_PtActivation(*in.ptActivation, out.pt_activation); out.pt_activation_is_present = true; } + } void toStruct_PublicTransportContainer(const cam_msgs::PublicTransportContainer& in, PublicTransportContainer_t& out) { + memset(&out, 0, sizeof(PublicTransportContainer_t)); toStruct_EmbarkationStatus(in.embarkation_status, out.embarkationStatus); if (in.pt_activation_is_present) { - out.ptActivation = (PtActivation_t*) calloc(1, sizeof(PtActivation_t)); - toStruct_PtActivation(in.pt_activation, *out.ptActivation); + PtActivation_t pt_activation; + toStruct_PtActivation(in.pt_activation, pt_activation); + out.ptActivation = new PtActivation_t(pt_activation); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h index 8b9fffcb9..93f4f6db8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRSUContainerHighFrequency.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -41,19 +40,24 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RSUContainerHighFrequency(const RSUContainerHighFrequency_t& in, cam_msgs::RSUContainerHighFrequency& out) { + if (in.protectedCommunicationZonesRSU) { toRos_ProtectedCommunicationZonesRSU(*in.protectedCommunicationZonesRSU, out.protected_communication_zones_rsu); out.protected_communication_zones_rsu_is_present = true; } + } void toStruct_RSUContainerHighFrequency(const cam_msgs::RSUContainerHighFrequency& in, RSUContainerHighFrequency_t& out) { + memset(&out, 0, sizeof(RSUContainerHighFrequency_t)); if (in.protected_communication_zones_rsu_is_present) { - out.protectedCommunicationZonesRSU = (ProtectedCommunicationZonesRSU_t*) calloc(1, sizeof(ProtectedCommunicationZonesRSU_t)); - toStruct_ProtectedCommunicationZonesRSU(in.protected_communication_zones_rsu, *out.protectedCommunicationZonesRSU); + ProtectedCommunicationZonesRSU_t protected_communication_zones_rsu; + toStruct_ProtectedCommunicationZonesRSU(in.protected_communication_zones_rsu, protected_communication_zones_rsu); + out.protectedCommunicationZonesRSU = new ProtectedCommunicationZonesRSU_t(protected_communication_zones_rsu); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h index 7035f32f8..c3dce3d24 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertReferencePosition.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,10 +27,10 @@ SOFTWARE. #pragma once #include -#include #include #include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -44,6 +43,7 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ReferencePosition(const ReferencePosition_t& in, cam_msgs::ReferencePosition& out) { + toRos_Latitude(in.latitude, out.latitude); toRos_Longitude(in.longitude, out.longitude); toRos_PosConfidenceEllipse(in.positionConfidenceEllipse, out.position_confidence_ellipse); @@ -51,6 +51,7 @@ void toRos_ReferencePosition(const ReferencePosition_t& in, cam_msgs::ReferenceP } void toStruct_ReferencePosition(const cam_msgs::ReferencePosition& in, ReferencePosition_t& out) { + memset(&out, 0, sizeof(ReferencePosition_t)); toStruct_Latitude(in.latitude, out.latitude); @@ -59,4 +60,4 @@ void toStruct_ReferencePosition(const cam_msgs::ReferencePosition& in, Reference toStruct_Altitude(in.altitude, out.altitude); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h index 73d7971d0..33b05e423 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceDistance.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RelevanceDistance(const RelevanceDistance_t& in, cam_msgs::RelevanceDistance& out) { + out.value = in; } void toStruct_RelevanceDistance(const cam_msgs::RelevanceDistance& in, RelevanceDistance_t& out) { - memset(&out, 0, sizeof(RelevanceDistance_t)); + memset(&out, 0, sizeof(RelevanceDistance_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h index 00c73e547..cc52bd9f6 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRelevanceTrafficDirection.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RelevanceTrafficDirection(const RelevanceTrafficDirection_t& in, cam_msgs::RelevanceTrafficDirection& out) { + out.value = in; } void toStruct_RelevanceTrafficDirection(const cam_msgs::RelevanceTrafficDirection& in, RelevanceTrafficDirection_t& out) { - memset(&out, 0, sizeof(RelevanceTrafficDirection_t)); + memset(&out, 0, sizeof(RelevanceTrafficDirection_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h index 2c9c8c854..b999a9457 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRequestResponseIndication.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RequestResponseIndication(const RequestResponseIndication_t& in, cam_msgs::RequestResponseIndication& out) { + out.value = in; } void toStruct_RequestResponseIndication(const cam_msgs::RequestResponseIndication& in, RequestResponseIndication_t& out) { - memset(&out, 0, sizeof(RequestResponseIndication_t)); + memset(&out, 0, sizeof(RequestResponseIndication_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index ee851e760..190dfecfd 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RescueAndRecoveryWorkInProgressSubCauseCode(const RescueAndRecoveryWorkInProgressSubCauseCode_t& in, cam_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RescueAndRecoveryWorkInProgressSubCauseCode(const cam_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& in, RescueAndRecoveryWorkInProgressSubCauseCode_t& out) { - memset(&out, 0, sizeof(RescueAndRecoveryWorkInProgressSubCauseCode_t)); + memset(&out, 0, sizeof(RescueAndRecoveryWorkInProgressSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h index fc41c8961..543cd5a82 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRescueContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -41,13 +40,15 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RescueContainer(const RescueContainer_t& in, cam_msgs::RescueContainer& out) { + toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); } void toStruct_RescueContainer(const cam_msgs::RescueContainer& in, RescueContainer_t& out) { + memset(&out, 0, sizeof(RescueContainer_t)); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h index f70b54f0e..144ef7723 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRestrictedTypes.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RestrictedTypes(const RestrictedTypes_t& in, cam_msgs::RestrictedTypes& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::StationType el; - toRos_StationType(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::StationType array; + toRos_StationType(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_RestrictedTypes(const cam_msgs::RestrictedTypes& in, RestrictedTypes_t& out) { + memset(&out, 0, sizeof(RestrictedTypes_t)); - for (int i = 0; i < in.array.size(); ++i) { - StationType_t* el = (StationType_t*) calloc(1, sizeof(StationType_t)); - toStruct_StationType(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + StationType_t array; + toStruct_StationType(in.array[i], array); + StationType_t* array_ptr = new StationType_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h index b39115f0f..8e6e7c95e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RoadType(const RoadType_t& in, cam_msgs::RoadType& out) { + out.value = in; } void toStruct_RoadType(const cam_msgs::RoadType& in, RoadType_t& out) { - memset(&out, 0, sizeof(RoadType_t)); + memset(&out, 0, sizeof(RoadType_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h index 6f2486354..ed41f19c0 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadWorksContainerBasic.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -43,29 +42,37 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RoadWorksContainerBasic(const RoadWorksContainerBasic_t& in, cam_msgs::RoadWorksContainerBasic& out) { + if (in.roadworksSubCauseCode) { toRos_RoadworksSubCauseCode(*in.roadworksSubCauseCode, out.roadworks_sub_cause_code); out.roadworks_sub_cause_code_is_present = true; } + toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); if (in.closedLanes) { toRos_ClosedLanes(*in.closedLanes, out.closed_lanes); out.closed_lanes_is_present = true; } + } void toStruct_RoadWorksContainerBasic(const cam_msgs::RoadWorksContainerBasic& in, RoadWorksContainerBasic_t& out) { + memset(&out, 0, sizeof(RoadWorksContainerBasic_t)); if (in.roadworks_sub_cause_code_is_present) { - out.roadworksSubCauseCode = (RoadworksSubCauseCode_t*) calloc(1, sizeof(RoadworksSubCauseCode_t)); - toStruct_RoadworksSubCauseCode(in.roadworks_sub_cause_code, *out.roadworksSubCauseCode); + RoadworksSubCauseCode_t roadworks_sub_cause_code; + toStruct_RoadworksSubCauseCode(in.roadworks_sub_cause_code, roadworks_sub_cause_code); + out.roadworksSubCauseCode = new RoadworksSubCauseCode_t(roadworks_sub_cause_code); } + toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); if (in.closed_lanes_is_present) { - out.closedLanes = (ClosedLanes_t*) calloc(1, sizeof(ClosedLanes_t)); - toStruct_ClosedLanes(in.closed_lanes, *out.closedLanes); + ClosedLanes_t closed_lanes; + toStruct_ClosedLanes(in.closed_lanes, closed_lanes); + out.closedLanes = new ClosedLanes_t(closed_lanes); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h index 892274129..d19dca4e4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertRoadworksSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_RoadworksSubCauseCode(const RoadworksSubCauseCode_t& in, cam_msgs::RoadworksSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RoadworksSubCauseCode(const cam_msgs::RoadworksSubCauseCode& in, RoadworksSubCauseCode_t& out) { - memset(&out, 0, sizeof(RoadworksSubCauseCode_t)); + memset(&out, 0, sizeof(RoadworksSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h index 8348ad994..1f081af63 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSafetyCarContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,10 +27,10 @@ SOFTWARE. #pragma once #include -#include #include -#include +#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -44,37 +43,48 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SafetyCarContainer(const SafetyCarContainer_t& in, cam_msgs::SafetyCarContainer& out) { + toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); if (in.incidentIndication) { toRos_CauseCode(*in.incidentIndication, out.incident_indication); out.incident_indication_is_present = true; } + if (in.trafficRule) { toRos_TrafficRule(*in.trafficRule, out.traffic_rule); out.traffic_rule_is_present = true; } + if (in.speedLimit) { toRos_SpeedLimit(*in.speedLimit, out.speed_limit); out.speed_limit_is_present = true; } + } void toStruct_SafetyCarContainer(const cam_msgs::SafetyCarContainer& in, SafetyCarContainer_t& out) { + memset(&out, 0, sizeof(SafetyCarContainer_t)); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); if (in.incident_indication_is_present) { - out.incidentIndication = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); - toStruct_CauseCode(in.incident_indication, *out.incidentIndication); + CauseCode_t incident_indication; + toStruct_CauseCode(in.incident_indication, incident_indication); + out.incidentIndication = new CauseCode_t(incident_indication); } + if (in.traffic_rule_is_present) { - out.trafficRule = (TrafficRule_t*) calloc(1, sizeof(TrafficRule_t)); - toStruct_TrafficRule(in.traffic_rule, *out.trafficRule); + TrafficRule_t traffic_rule; + toStruct_TrafficRule(in.traffic_rule, traffic_rule); + out.trafficRule = new TrafficRule_t(traffic_rule); } + if (in.speed_limit_is_present) { - out.speedLimit = (SpeedLimit_t*) calloc(1, sizeof(SpeedLimit_t)); - toStruct_SpeedLimit(in.speed_limit, *out.speedLimit); + SpeedLimit_t speed_limit; + toStruct_SpeedLimit(in.speed_limit, speed_limit); + out.speedLimit = new SpeedLimit_t(speed_limit); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h index f30541b72..12fce5fd1 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSemiAxisLength.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SemiAxisLength(const SemiAxisLength_t& in, cam_msgs::SemiAxisLength& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SemiAxisLength(const cam_msgs::SemiAxisLength& in, SemiAxisLength_t& out) { - memset(&out, 0, sizeof(SemiAxisLength_t)); + memset(&out, 0, sizeof(SemiAxisLength_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h index db08cbb44..d81a019ea 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSequenceNumber.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SequenceNumber(const SequenceNumber_t& in, cam_msgs::SequenceNumber& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SequenceNumber(const cam_msgs::SequenceNumber& in, SequenceNumber_t& out) { - memset(&out, 0, sizeof(SequenceNumber_t)); + memset(&out, 0, sizeof(SequenceNumber_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h index 00dc05ff3..468179bd3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSignalViolationSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SignalViolationSubCauseCode(const SignalViolationSubCauseCode_t& in, cam_msgs::SignalViolationSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SignalViolationSubCauseCode(const cam_msgs::SignalViolationSubCauseCode& in, SignalViolationSubCauseCode_t& out) { - memset(&out, 0, sizeof(SignalViolationSubCauseCode_t)); + memset(&out, 0, sizeof(SignalViolationSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h index 57f3b0c56..7403604ce 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSlowVehicleSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SlowVehicleSubCauseCode(const SlowVehicleSubCauseCode_t& in, cam_msgs::SlowVehicleSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SlowVehicleSubCauseCode(const cam_msgs::SlowVehicleSubCauseCode& in, SlowVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(SlowVehicleSubCauseCode_t)); + memset(&out, 0, sizeof(SlowVehicleSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h index 3eaa0f084..ad068765c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpecialTransportContainer(const SpecialTransportContainer_t& in, cam_msgs::SpecialTransportContainer& out) { + toRos_SpecialTransportType(in.specialTransportType, out.special_transport_type); toRos_LightBarSirenInUse(in.lightBarSirenInUse, out.light_bar_siren_in_use); } void toStruct_SpecialTransportContainer(const cam_msgs::SpecialTransportContainer& in, SpecialTransportContainer_t& out) { + memset(&out, 0, sizeof(SpecialTransportContainer_t)); toStruct_SpecialTransportType(in.special_transport_type, out.specialTransportType); toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, out.lightBarSirenInUse); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h index 3c16d029b..4c4444634 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialTransportType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpecialTransportType(const SpecialTransportType_t& in, cam_msgs::SpecialTransportType& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_SpecialTransportType(const cam_msgs::SpecialTransportType& in, SpecialTransportType_t& out) { - memset(&out, 0, sizeof(SpecialTransportType_t)); + memset(&out, 0, sizeof(SpecialTransportType_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h index dc444b681..6ebd44506 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpecialVehicleContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,13 +27,13 @@ SOFTWARE. #pragma once #include -#include -#include #include -#include +#include +#include #include +#include +#include #include -#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -47,73 +46,82 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpecialVehicleContainer(const SpecialVehicleContainer_t& in, cam_msgs::SpecialVehicleContainer& out) { - switch (in.present) { - case SpecialVehicleContainer_PR_publicTransportContainer: + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_publicTransportContainer) { toRos_PublicTransportContainer(in.choice.publicTransportContainer, out.public_transport_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_PUBLIC_TRANSPORT_CONTAINER; - break; - case SpecialVehicleContainer_PR_specialTransportContainer: + } + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_specialTransportContainer) { toRos_SpecialTransportContainer(in.choice.specialTransportContainer, out.special_transport_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_SPECIAL_TRANSPORT_CONTAINER; - break; - case SpecialVehicleContainer_PR_dangerousGoodsContainer: + } + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_dangerousGoodsContainer) { toRos_DangerousGoodsContainer(in.choice.dangerousGoodsContainer, out.dangerous_goods_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_DANGEROUS_GOODS_CONTAINER; - break; - case SpecialVehicleContainer_PR_roadWorksContainerBasic: + } + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_roadWorksContainerBasic) { toRos_RoadWorksContainerBasic(in.choice.roadWorksContainerBasic, out.road_works_container_basic); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_ROAD_WORKS_CONTAINER_BASIC; - break; - case SpecialVehicleContainer_PR_rescueContainer: + } + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_rescueContainer) { toRos_RescueContainer(in.choice.rescueContainer, out.rescue_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_RESCUE_CONTAINER; - break; - case SpecialVehicleContainer_PR_emergencyContainer: + } + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_emergencyContainer) { toRos_EmergencyContainer(in.choice.emergencyContainer, out.emergency_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_EMERGENCY_CONTAINER; - break; - case SpecialVehicleContainer_PR_safetyCarContainer: + } + + if (in.present == SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_safetyCarContainer) { toRos_SafetyCarContainer(in.choice.safetyCarContainer, out.safety_car_container); out.choice = cam_msgs::SpecialVehicleContainer::CHOICE_SAFETY_CAR_CONTAINER; - break; - default: break; } } void toStruct_SpecialVehicleContainer(const cam_msgs::SpecialVehicleContainer& in, SpecialVehicleContainer_t& out) { + memset(&out, 0, sizeof(SpecialVehicleContainer_t)); - switch (in.choice) { - case cam_msgs::SpecialVehicleContainer::CHOICE_PUBLIC_TRANSPORT_CONTAINER: + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_PUBLIC_TRANSPORT_CONTAINER) { toStruct_PublicTransportContainer(in.public_transport_container, out.choice.publicTransportContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_publicTransportContainer; - break; - case cam_msgs::SpecialVehicleContainer::CHOICE_SPECIAL_TRANSPORT_CONTAINER: + } + + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_SPECIAL_TRANSPORT_CONTAINER) { toStruct_SpecialTransportContainer(in.special_transport_container, out.choice.specialTransportContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_specialTransportContainer; - break; - case cam_msgs::SpecialVehicleContainer::CHOICE_DANGEROUS_GOODS_CONTAINER: + } + + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_DANGEROUS_GOODS_CONTAINER) { toStruct_DangerousGoodsContainer(in.dangerous_goods_container, out.choice.dangerousGoodsContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_dangerousGoodsContainer; - break; - case cam_msgs::SpecialVehicleContainer::CHOICE_ROAD_WORKS_CONTAINER_BASIC: + } + + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_ROAD_WORKS_CONTAINER_BASIC) { toStruct_RoadWorksContainerBasic(in.road_works_container_basic, out.choice.roadWorksContainerBasic); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_roadWorksContainerBasic; - break; - case cam_msgs::SpecialVehicleContainer::CHOICE_RESCUE_CONTAINER: + } + + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_RESCUE_CONTAINER) { toStruct_RescueContainer(in.rescue_container, out.choice.rescueContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_rescueContainer; - break; - case cam_msgs::SpecialVehicleContainer::CHOICE_EMERGENCY_CONTAINER: + } + + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_EMERGENCY_CONTAINER) { toStruct_EmergencyContainer(in.emergency_container, out.choice.emergencyContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_emergencyContainer; - break; - case cam_msgs::SpecialVehicleContainer::CHOICE_SAFETY_CAR_CONTAINER: + } + + if (in.choice == cam_msgs::SpecialVehicleContainer::CHOICE_SAFETY_CAR_CONTAINER) { toStruct_SafetyCarContainer(in.safety_car_container, out.choice.safetyCarContainer); out.present = SpecialVehicleContainer_PR::SpecialVehicleContainer_PR_safetyCarContainer; - break; - default: break; } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h index 080ed619c..8c6a6ab79 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeed.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Speed(const Speed_t& in, cam_msgs::Speed& out) { + toRos_SpeedValue(in.speedValue, out.speed_value); toRos_SpeedConfidence(in.speedConfidence, out.speed_confidence); } void toStruct_Speed(const cam_msgs::Speed& in, Speed_t& out) { + memset(&out, 0, sizeof(Speed_t)); toStruct_SpeedValue(in.speed_value, out.speedValue); toStruct_SpeedConfidence(in.speed_confidence, out.speedConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h index 44aa34d2c..6830fd601 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpeedConfidence(const SpeedConfidence_t& in, cam_msgs::SpeedConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedConfidence(const cam_msgs::SpeedConfidence& in, SpeedConfidence_t& out) { - memset(&out, 0, sizeof(SpeedConfidence_t)); + memset(&out, 0, sizeof(SpeedConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h index 0c92df001..10712953e 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedLimit.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpeedLimit(const SpeedLimit_t& in, cam_msgs::SpeedLimit& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedLimit(const cam_msgs::SpeedLimit& in, SpeedLimit_t& out) { - memset(&out, 0, sizeof(SpeedLimit_t)); + memset(&out, 0, sizeof(SpeedLimit_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h index 66082b8c1..82536bb4f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSpeedValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SpeedValue(const SpeedValue_t& in, cam_msgs::SpeedValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedValue(const cam_msgs::SpeedValue& in, SpeedValue_t& out) { - memset(&out, 0, sizeof(SpeedValue_t)); + memset(&out, 0, sizeof(SpeedValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h index 7c3f10aa7..65e0410b3 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationID(const StationID_t& in, cam_msgs::StationID& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationID(const cam_msgs::StationID& in, StationID_t& out) { - memset(&out, 0, sizeof(StationID_t)); + memset(&out, 0, sizeof(StationID_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h index 41fd6a4e1..b36956ad4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationType(const StationType_t& in, cam_msgs::StationType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationType(const cam_msgs::StationType& in, StationType_t& out) { - memset(&out, 0, sizeof(StationType_t)); + memset(&out, 0, sizeof(StationType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h index d892fce8b..e08a57d70 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationarySince.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationarySince(const StationarySince_t& in, cam_msgs::StationarySince& out) { + out.value = in; } void toStruct_StationarySince(const cam_msgs::StationarySince& in, StationarySince_t& out) { - memset(&out, 0, sizeof(StationarySince_t)); + memset(&out, 0, sizeof(StationarySince_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h index 5e19fb88f..3612d7dd9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertStationaryVehicleSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_StationaryVehicleSubCauseCode(const StationaryVehicleSubCauseCode_t& in, cam_msgs::StationaryVehicleSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationaryVehicleSubCauseCode(const cam_msgs::StationaryVehicleSubCauseCode& in, StationaryVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(StationaryVehicleSubCauseCode_t)); + memset(&out, 0, sizeof(StationaryVehicleSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h index e76d88fdb..876b41023 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngle.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SteeringWheelAngle(const SteeringWheelAngle_t& in, cam_msgs::SteeringWheelAngle& out) { + toRos_SteeringWheelAngleValue(in.steeringWheelAngleValue, out.steering_wheel_angle_value); toRos_SteeringWheelAngleConfidence(in.steeringWheelAngleConfidence, out.steering_wheel_angle_confidence); } void toStruct_SteeringWheelAngle(const cam_msgs::SteeringWheelAngle& in, SteeringWheelAngle_t& out) { + memset(&out, 0, sizeof(SteeringWheelAngle_t)); toStruct_SteeringWheelAngleValue(in.steering_wheel_angle_value, out.steeringWheelAngleValue); toStruct_SteeringWheelAngleConfidence(in.steering_wheel_angle_confidence, out.steeringWheelAngleConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h index 005f4baf2..0971a23df 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SteeringWheelAngleConfidence(const SteeringWheelAngleConfidence_t& in, cam_msgs::SteeringWheelAngleConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleConfidence(const cam_msgs::SteeringWheelAngleConfidence& in, SteeringWheelAngleConfidence_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleConfidence_t)); + memset(&out, 0, sizeof(SteeringWheelAngleConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h index d604f2ee0..beeb5b64f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSteeringWheelAngleValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SteeringWheelAngleValue(const SteeringWheelAngleValue_t& in, cam_msgs::SteeringWheelAngleValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleValue(const cam_msgs::SteeringWheelAngleValue& in, SteeringWheelAngleValue_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleValue_t)); + memset(&out, 0, sizeof(SteeringWheelAngleValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h index f59ea7c77..92cfb62ca 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertSubCauseCodeType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_SubCauseCodeType(const SubCauseCodeType_t& in, cam_msgs::SubCauseCodeType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SubCauseCodeType(const cam_msgs::SubCauseCodeType& in, SubCauseCodeType_t& out) { - memset(&out, 0, sizeof(SubCauseCodeType_t)); + memset(&out, 0, sizeof(SubCauseCodeType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h index ec3f787e9..19a18da5a 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTemperature.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Temperature(const Temperature_t& in, cam_msgs::Temperature& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Temperature(const cam_msgs::Temperature& in, Temperature_t& out) { - memset(&out, 0, sizeof(Temperature_t)); + memset(&out, 0, sizeof(Temperature_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h index 37192c152..f12b36da5 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTimestampIts.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TimestampIts(const TimestampIts_t& in, cam_msgs::TimestampIts& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TimestampIts(const cam_msgs::TimestampIts& in, TimestampIts_t& out) { - memset(&out, 0, sizeof(TimestampIts_t)); + memset(&out, 0, sizeof(TimestampIts_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h index 7d6722766..fcaa3668c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTraces.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace cam_msgs = etsi_its_cam_msgs; #else +#include #include namespace cam_msgs = etsi_its_cam_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_Traces(const Traces_t& in, cam_msgs::Traces& out) { - for (int i = 0; i < in.list.count; ++i) { - cam_msgs::PathHistory el; - toRos_PathHistory(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + cam_msgs::PathHistory array; + toRos_PathHistory(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_Traces(const cam_msgs::Traces& in, Traces_t& out) { + memset(&out, 0, sizeof(Traces_t)); - for (int i = 0; i < in.array.size(); ++i) { - PathHistory_t* el = (PathHistory_t*) calloc(1, sizeof(PathHistory_t)); - toStruct_PathHistory(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + PathHistory_t array; + toStruct_PathHistory(in.array[i], array); + PathHistory_t* array_ptr = new PathHistory_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h index 5b9b812bf..e3e82d758 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficConditionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TrafficConditionSubCauseCode(const TrafficConditionSubCauseCode_t& in, cam_msgs::TrafficConditionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TrafficConditionSubCauseCode(const cam_msgs::TrafficConditionSubCauseCode& in, TrafficConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(TrafficConditionSubCauseCode_t)); + memset(&out, 0, sizeof(TrafficConditionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h index 2b339375a..badd4b3be 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTrafficRule.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TrafficRule(const TrafficRule_t& in, cam_msgs::TrafficRule& out) { + out.value = in; } void toStruct_TrafficRule(const cam_msgs::TrafficRule& in, TrafficRule_t& out) { - memset(&out, 0, sizeof(TrafficRule_t)); + memset(&out, 0, sizeof(TrafficRule_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h index 8791b61b9..c120ee048 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTransmissionInterval.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TransmissionInterval(const TransmissionInterval_t& in, cam_msgs::TransmissionInterval& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TransmissionInterval(const cam_msgs::TransmissionInterval& in, TransmissionInterval_t& out) { - memset(&out, 0, sizeof(TransmissionInterval_t)); + memset(&out, 0, sizeof(TransmissionInterval_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h index 27b9c851b..932813d6c 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertTurningRadius.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_TurningRadius(const TurningRadius_t& in, cam_msgs::TurningRadius& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TurningRadius(const cam_msgs::TurningRadius& in, TurningRadius_t& out) { - memset(&out, 0, sizeof(TurningRadius_t)); + memset(&out, 0, sizeof(TurningRadius_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h index 28471b4c8..a11c4c450 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVDS.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VDS(const VDS_t& in, cam_msgs::VDS& out) { + etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_VDS(const cam_msgs::VDS& in, VDS_t& out) { - memset(&out, 0, sizeof(VDS_t)); + memset(&out, 0, sizeof(VDS_t)); etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h index 667d26415..a9a0bbd24 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertValidityDuration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_ValidityDuration(const ValidityDuration_t& in, cam_msgs::ValidityDuration& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ValidityDuration(const cam_msgs::ValidityDuration& in, ValidityDuration_t& out) { - memset(&out, 0, sizeof(ValidityDuration_t)); + memset(&out, 0, sizeof(ValidityDuration_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h index 7deb90d3f..9eb5fd145 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleBreakdownSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleBreakdownSubCauseCode(const VehicleBreakdownSubCauseCode_t& in, cam_msgs::VehicleBreakdownSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleBreakdownSubCauseCode(const cam_msgs::VehicleBreakdownSubCauseCode& in, VehicleBreakdownSubCauseCode_t& out) { - memset(&out, 0, sizeof(VehicleBreakdownSubCauseCode_t)); + memset(&out, 0, sizeof(VehicleBreakdownSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h index fef5d71f0..786a6a8bc 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleIdentification.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,27 +41,35 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleIdentification(const VehicleIdentification_t& in, cam_msgs::VehicleIdentification& out) { + if (in.wMInumber) { - toRos_WMInumber(*in.wMInumber, out.w_m_inumber); - out.w_m_inumber_is_present = true; + toRos_WMInumber(*in.wMInumber, out.wm_inumber); + out.wm_inumber_is_present = true; } + if (in.vDS) { - toRos_VDS(*in.vDS, out.v_ds); - out.v_ds_is_present = true; + toRos_VDS(*in.vDS, out.vds); + out.vds_is_present = true; } + } void toStruct_VehicleIdentification(const cam_msgs::VehicleIdentification& in, VehicleIdentification_t& out) { + memset(&out, 0, sizeof(VehicleIdentification_t)); - if (in.w_m_inumber_is_present) { - out.wMInumber = (WMInumber_t*) calloc(1, sizeof(WMInumber_t)); - toStruct_WMInumber(in.w_m_inumber, *out.wMInumber); + if (in.wm_inumber_is_present) { + WMInumber_t wm_inumber; + toStruct_WMInumber(in.wm_inumber, wm_inumber); + out.wMInumber = new WMInumber_t(wm_inumber); } - if (in.v_ds_is_present) { - out.vDS = (VDS_t*) calloc(1, sizeof(VDS_t)); - toStruct_VDS(in.v_ds, *out.vDS); + + if (in.vds_is_present) { + VDS_t vds; + toStruct_VDS(in.vds, vds); + out.vDS = new VDS_t(vds); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h index 328748db2..a95466a17 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLength.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleLength(const VehicleLength_t& in, cam_msgs::VehicleLength& out) { + toRos_VehicleLengthValue(in.vehicleLengthValue, out.vehicle_length_value); toRos_VehicleLengthConfidenceIndication(in.vehicleLengthConfidenceIndication, out.vehicle_length_confidence_indication); } void toStruct_VehicleLength(const cam_msgs::VehicleLength& in, VehicleLength_t& out) { + memset(&out, 0, sizeof(VehicleLength_t)); toStruct_VehicleLengthValue(in.vehicle_length_value, out.vehicleLengthValue); toStruct_VehicleLengthConfidenceIndication(in.vehicle_length_confidence_indication, out.vehicleLengthConfidenceIndication); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h index c449e4673..dbc1eed72 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthConfidenceIndication.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleLengthConfidenceIndication(const VehicleLengthConfidenceIndication_t& in, cam_msgs::VehicleLengthConfidenceIndication& out) { + out.value = in; } void toStruct_VehicleLengthConfidenceIndication(const cam_msgs::VehicleLengthConfidenceIndication& in, VehicleLengthConfidenceIndication_t& out) { - memset(&out, 0, sizeof(VehicleLengthConfidenceIndication_t)); + memset(&out, 0, sizeof(VehicleLengthConfidenceIndication_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h index 14745d64c..74afa359f 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleLengthValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleLengthValue(const VehicleLengthValue_t& in, cam_msgs::VehicleLengthValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleLengthValue(const cam_msgs::VehicleLengthValue& in, VehicleLengthValue_t& out) { - memset(&out, 0, sizeof(VehicleLengthValue_t)); + memset(&out, 0, sizeof(VehicleLengthValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h index 6b62da4ee..e51e1c924 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleMass.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleMass(const VehicleMass_t& in, cam_msgs::VehicleMass& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleMass(const cam_msgs::VehicleMass& in, VehicleMass_t& out) { - memset(&out, 0, sizeof(VehicleMass_t)); + memset(&out, 0, sizeof(VehicleMass_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h index 604727281..19bf81331 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleRole.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleRole(const VehicleRole_t& in, cam_msgs::VehicleRole& out) { + out.value = in; } void toStruct_VehicleRole(const cam_msgs::VehicleRole& in, VehicleRole_t& out) { - memset(&out, 0, sizeof(VehicleRole_t)); + memset(&out, 0, sizeof(VehicleRole_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h index 642a3561b..7b9e2a904 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVehicleWidth.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VehicleWidth(const VehicleWidth_t& in, cam_msgs::VehicleWidth& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleWidth(const cam_msgs::VehicleWidth& in, VehicleWidth_t& out) { - memset(&out, 0, sizeof(VehicleWidth_t)); + memset(&out, 0, sizeof(VehicleWidth_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h index ee9e4d62b..68267c305 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAcceleration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VerticalAcceleration(const VerticalAcceleration_t& in, cam_msgs::VerticalAcceleration& out) { + toRos_VerticalAccelerationValue(in.verticalAccelerationValue, out.vertical_acceleration_value); toRos_AccelerationConfidence(in.verticalAccelerationConfidence, out.vertical_acceleration_confidence); } void toStruct_VerticalAcceleration(const cam_msgs::VerticalAcceleration& in, VerticalAcceleration_t& out) { + memset(&out, 0, sizeof(VerticalAcceleration_t)); toStruct_VerticalAccelerationValue(in.vertical_acceleration_value, out.verticalAccelerationValue); toStruct_AccelerationConfidence(in.vertical_acceleration_confidence, out.verticalAccelerationConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h index 62de438e2..5e74c8131 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertVerticalAccelerationValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_VerticalAccelerationValue(const VerticalAccelerationValue_t& in, cam_msgs::VerticalAccelerationValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VerticalAccelerationValue(const cam_msgs::VerticalAccelerationValue& in, VerticalAccelerationValue_t& out) { - memset(&out, 0, sizeof(VerticalAccelerationValue_t)); + memset(&out, 0, sizeof(VerticalAccelerationValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h index 681712d2d..178ba1ef4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWMInumber.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_WMInumber(const WMInumber_t& in, cam_msgs::WMInumber& out) { + etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_WMInumber(const cam_msgs::WMInumber& in, WMInumber_t& out) { - memset(&out, 0, sizeof(WMInumber_t)); + memset(&out, 0, sizeof(WMInumber_t)); etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h index 3dd2ccfe0..f292aa1a4 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWheelBaseVehicle.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_WheelBaseVehicle(const WheelBaseVehicle_t& in, cam_msgs::WheelBaseVehicle& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WheelBaseVehicle(const cam_msgs::WheelBaseVehicle& in, WheelBaseVehicle_t& out) { - memset(&out, 0, sizeof(WheelBaseVehicle_t)); + memset(&out, 0, sizeof(WheelBaseVehicle_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h index fa9da94ed..19aeb32c9 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertWrongWayDrivingSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_WrongWayDrivingSubCauseCode(const WrongWayDrivingSubCauseCode_t& in, cam_msgs::WrongWayDrivingSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WrongWayDrivingSubCauseCode(const cam_msgs::WrongWayDrivingSubCauseCode& in, WrongWayDrivingSubCauseCode_t& out) { - memset(&out, 0, sizeof(WrongWayDrivingSubCauseCode_t)); + memset(&out, 0, sizeof(WrongWayDrivingSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h index 2fc8887d3..24784a875 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRate.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -42,15 +41,17 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_YawRate(const YawRate_t& in, cam_msgs::YawRate& out) { + toRos_YawRateValue(in.yawRateValue, out.yaw_rate_value); toRos_YawRateConfidence(in.yawRateConfidence, out.yaw_rate_confidence); } void toStruct_YawRate(const cam_msgs::YawRate& in, YawRate_t& out) { + memset(&out, 0, sizeof(YawRate_t)); toStruct_YawRateValue(in.yaw_rate_value, out.yawRateValue); toStruct_YawRateConfidence(in.yaw_rate_confidence, out.yawRateConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h index d650f6ac2..067f7bda8 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace cam_msgs = etsi_its_cam_msgs; @@ -41,13 +39,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_YawRateConfidence(const YawRateConfidence_t& in, cam_msgs::YawRateConfidence& out) { + out.value = in; } void toStruct_YawRateConfidence(const cam_msgs::YawRateConfidence& in, YawRateConfidence_t& out) { - memset(&out, 0, sizeof(YawRateConfidence_t)); + memset(&out, 0, sizeof(YawRateConfidence_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h index f00935a2d..c6bfef717 100644 --- a/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_cam_conversion/include/etsi_its_cam_conversion/convertYawRateValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace cam_msgs = etsi_its_cam_msgs::msg; namespace etsi_its_cam_conversion { void toRos_YawRateValue(const YawRateValue_t& in, cam_msgs::YawRateValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_YawRateValue(const cam_msgs::YawRateValue& in, YawRateValue_t& out) { - memset(&out, 0, sizeof(YawRateValue_t)); + memset(&out, 0, sizeof(YawRateValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h index f38218e92..6f7576fe2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AccelerationConfidence(const AccelerationConfidence_t& in, denm_msgs::AccelerationConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccelerationConfidence(const denm_msgs::AccelerationConfidence& in, AccelerationConfidence_t& out) { - memset(&out, 0, sizeof(AccelerationConfidence_t)); + memset(&out, 0, sizeof(AccelerationConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h index 5eef43e59..ababe3fc3 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccelerationControl.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AccelerationControl(const AccelerationControl_t& in, denm_msgs::AccelerationControl& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_AccelerationControl(const denm_msgs::AccelerationControl& in, AccelerationControl_t& out) { - memset(&out, 0, sizeof(AccelerationControl_t)); + memset(&out, 0, sizeof(AccelerationControl_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h index 0135de6a9..f36634572 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAccidentSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AccidentSubCauseCode(const AccidentSubCauseCode_t& in, denm_msgs::AccidentSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AccidentSubCauseCode(const denm_msgs::AccidentSubCauseCode& in, AccidentSubCauseCode_t& out) { - memset(&out, 0, sizeof(AccidentSubCauseCode_t)); + memset(&out, 0, sizeof(AccidentSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h index ed518f1da..90bdda43f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertActionID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ActionID(const ActionID_t& in, denm_msgs::ActionID& out) { + toRos_StationID(in.originatingStationID, out.originating_station_id); toRos_SequenceNumber(in.sequenceNumber, out.sequence_number); } void toStruct_ActionID(const denm_msgs::ActionID& in, ActionID_t& out) { + memset(&out, 0, sizeof(ActionID_t)); toStruct_StationID(in.originating_station_id, out.originatingStationID); toStruct_SequenceNumber(in.sequence_number, out.sequenceNumber); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h index 452e555c8..c3a7c461c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionAdhesionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionAdhesionSubCauseCode(const AdverseWeatherCondition_AdhesionSubCauseCode_t& in, denm_msgs::AdverseWeatherConditionAdhesionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionAdhesionSubCauseCode(const denm_msgs::AdverseWeatherConditionAdhesionSubCauseCode& in, AdverseWeatherCondition_AdhesionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_AdhesionSubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_AdhesionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h index a763bc939..79ace78c2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionExtremeWeatherConditionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& in, denm_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionExtremeWeatherConditionSubCauseCode(const denm_msgs::AdverseWeatherConditionExtremeWeatherConditionSubCauseCode& in, AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_ExtremeWeatherConditionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h index d8890a145..205d287b9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionPrecipitationSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionPrecipitationSubCauseCode(const AdverseWeatherCondition_PrecipitationSubCauseCode_t& in, denm_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionPrecipitationSubCauseCode(const denm_msgs::AdverseWeatherConditionPrecipitationSubCauseCode& in, AdverseWeatherCondition_PrecipitationSubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_PrecipitationSubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_PrecipitationSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h index a7330e543..55b16ff8c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAdverseWeatherConditionVisibilitySubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AdverseWeatherConditionVisibilitySubCauseCode(const AdverseWeatherCondition_VisibilitySubCauseCode_t& in, denm_msgs::AdverseWeatherConditionVisibilitySubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AdverseWeatherConditionVisibilitySubCauseCode(const denm_msgs::AdverseWeatherConditionVisibilitySubCauseCode& in, AdverseWeatherCondition_VisibilitySubCauseCode_t& out) { - memset(&out, 0, sizeof(AdverseWeatherCondition_VisibilitySubCauseCode_t)); + memset(&out, 0, sizeof(AdverseWeatherCondition_VisibilitySubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h index 9ff31cd89..50a8ddcac 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAlacarteContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,12 +27,12 @@ SOFTWARE. #pragma once #include -#include #include -#include +#include +#include #include +#include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -46,59 +45,79 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AlacarteContainer(const AlacarteContainer_t& in, denm_msgs::AlacarteContainer& out) { + if (in.lanePosition) { toRos_LanePosition(*in.lanePosition, out.lane_position); out.lane_position_is_present = true; } + if (in.impactReduction) { toRos_ImpactReductionContainer(*in.impactReduction, out.impact_reduction); out.impact_reduction_is_present = true; } + if (in.externalTemperature) { toRos_Temperature(*in.externalTemperature, out.external_temperature); out.external_temperature_is_present = true; } + if (in.roadWorks) { toRos_RoadWorksContainerExtended(*in.roadWorks, out.road_works); out.road_works_is_present = true; } + if (in.positioningSolution) { toRos_PositioningSolutionType(*in.positioningSolution, out.positioning_solution); out.positioning_solution_is_present = true; } + if (in.stationaryVehicle) { toRos_StationaryVehicleContainer(*in.stationaryVehicle, out.stationary_vehicle); out.stationary_vehicle_is_present = true; } + } void toStruct_AlacarteContainer(const denm_msgs::AlacarteContainer& in, AlacarteContainer_t& out) { + memset(&out, 0, sizeof(AlacarteContainer_t)); if (in.lane_position_is_present) { - out.lanePosition = (LanePosition_t*) calloc(1, sizeof(LanePosition_t)); - toStruct_LanePosition(in.lane_position, *out.lanePosition); + LanePosition_t lane_position; + toStruct_LanePosition(in.lane_position, lane_position); + out.lanePosition = new LanePosition_t(lane_position); } + if (in.impact_reduction_is_present) { - out.impactReduction = (ImpactReductionContainer_t*) calloc(1, sizeof(ImpactReductionContainer_t)); - toStruct_ImpactReductionContainer(in.impact_reduction, *out.impactReduction); + ImpactReductionContainer_t impact_reduction; + toStruct_ImpactReductionContainer(in.impact_reduction, impact_reduction); + out.impactReduction = new ImpactReductionContainer_t(impact_reduction); } + if (in.external_temperature_is_present) { - out.externalTemperature = (Temperature_t*) calloc(1, sizeof(Temperature_t)); - toStruct_Temperature(in.external_temperature, *out.externalTemperature); + Temperature_t external_temperature; + toStruct_Temperature(in.external_temperature, external_temperature); + out.externalTemperature = new Temperature_t(external_temperature); } + if (in.road_works_is_present) { - out.roadWorks = (RoadWorksContainerExtended_t*) calloc(1, sizeof(RoadWorksContainerExtended_t)); - toStruct_RoadWorksContainerExtended(in.road_works, *out.roadWorks); + RoadWorksContainerExtended_t road_works; + toStruct_RoadWorksContainerExtended(in.road_works, road_works); + out.roadWorks = new RoadWorksContainerExtended_t(road_works); } + if (in.positioning_solution_is_present) { - out.positioningSolution = (PositioningSolutionType_t*) calloc(1, sizeof(PositioningSolutionType_t)); - toStruct_PositioningSolutionType(in.positioning_solution, *out.positioningSolution); + PositioningSolutionType_t positioning_solution; + toStruct_PositioningSolutionType(in.positioning_solution, positioning_solution); + out.positioningSolution = new PositioningSolutionType_t(positioning_solution); } + if (in.stationary_vehicle_is_present) { - out.stationaryVehicle = (StationaryVehicleContainer_t*) calloc(1, sizeof(StationaryVehicleContainer_t)); - toStruct_StationaryVehicleContainer(in.stationary_vehicle, *out.stationaryVehicle); + StationaryVehicleContainer_t stationary_vehicle; + toStruct_StationaryVehicleContainer(in.stationary_vehicle, stationary_vehicle); + out.stationaryVehicle = new StationaryVehicleContainer_t(stationary_vehicle); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h index 3f71894cb..f1d0c3b90 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Altitude(const Altitude_t& in, denm_msgs::Altitude& out) { + toRos_AltitudeValue(in.altitudeValue, out.altitude_value); toRos_AltitudeConfidence(in.altitudeConfidence, out.altitude_confidence); } void toStruct_Altitude(const denm_msgs::Altitude& in, Altitude_t& out) { + memset(&out, 0, sizeof(Altitude_t)); toStruct_AltitudeValue(in.altitude_value, out.altitudeValue); toStruct_AltitudeConfidence(in.altitude_confidence, out.altitudeConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h index 2a5a8714c..149a3ef87 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AltitudeConfidence(const AltitudeConfidence_t& in, denm_msgs::AltitudeConfidence& out) { + out.value = in; } void toStruct_AltitudeConfidence(const denm_msgs::AltitudeConfidence& in, AltitudeConfidence_t& out) { - memset(&out, 0, sizeof(AltitudeConfidence_t)); + memset(&out, 0, sizeof(AltitudeConfidence_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h index c6ceeda8a..ae5527343 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertAltitudeValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_AltitudeValue(const AltitudeValue_t& in, denm_msgs::AltitudeValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_AltitudeValue(const denm_msgs::AltitudeValue& in, AltitudeValue_t& out) { - memset(&out, 0, sizeof(AltitudeValue_t)); + memset(&out, 0, sizeof(AltitudeValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h index 68b8bd655..00e2d758a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CauseCode(const CauseCode_t& in, denm_msgs::CauseCode& out) { + toRos_CauseCodeType(in.causeCode, out.cause_code); toRos_SubCauseCodeType(in.subCauseCode, out.sub_cause_code); } void toStruct_CauseCode(const denm_msgs::CauseCode& in, CauseCode_t& out) { + memset(&out, 0, sizeof(CauseCode_t)); toStruct_CauseCodeType(in.cause_code, out.causeCode); toStruct_SubCauseCodeType(in.sub_cause_code, out.subCauseCode); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h index a9ff68ed2..2f6fda285 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCauseCodeType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CauseCodeType(const CauseCodeType_t& in, denm_msgs::CauseCodeType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CauseCodeType(const denm_msgs::CauseCodeType& in, CauseCodeType_t& out) { - memset(&out, 0, sizeof(CauseCodeType_t)); + memset(&out, 0, sizeof(CauseCodeType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h index a2e074b3f..0e482b9af 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZone.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -43,23 +42,28 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CenDsrcTollingZone(const CenDsrcTollingZone_t& in, denm_msgs::CenDsrcTollingZone& out) { + toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.cenDsrcTollingZoneID) { toRos_CenDsrcTollingZoneID(*in.cenDsrcTollingZoneID, out.cen_dsrc_tolling_zone_id); out.cen_dsrc_tolling_zone_id_is_present = true; } + } void toStruct_CenDsrcTollingZone(const denm_msgs::CenDsrcTollingZone& in, CenDsrcTollingZone_t& out) { + memset(&out, 0, sizeof(CenDsrcTollingZone_t)); toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.cen_dsrc_tolling_zone_id_is_present) { - out.cenDsrcTollingZoneID = (CenDsrcTollingZoneID_t*) calloc(1, sizeof(CenDsrcTollingZoneID_t)); - toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, *out.cenDsrcTollingZoneID); + CenDsrcTollingZoneID_t cen_dsrc_tolling_zone_id; + toStruct_CenDsrcTollingZoneID(in.cen_dsrc_tolling_zone_id, cen_dsrc_tolling_zone_id); + out.cenDsrcTollingZoneID = new CenDsrcTollingZoneID_t(cen_dsrc_tolling_zone_id); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h index 237b7a17e..7ff1f0447 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCenDsrcTollingZoneID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -37,17 +36,17 @@ namespace denm_msgs = etsi_its_denm_msgs; namespace denm_msgs = etsi_its_denm_msgs::msg; #endif - namespace etsi_its_denm_conversion { void toRos_CenDsrcTollingZoneID(const CenDsrcTollingZoneID_t& in, denm_msgs::CenDsrcTollingZoneID& out) { + toRos_ProtectedZoneID(in, out.value); } void toStruct_CenDsrcTollingZoneID(const denm_msgs::CenDsrcTollingZoneID& in, CenDsrcTollingZoneID_t& out) { - memset(&out, 0, sizeof(CenDsrcTollingZoneID_t)); + memset(&out, 0, sizeof(CenDsrcTollingZoneID_t)); toStruct_ProtectedZoneID(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h index f9857a0f5..401a0d560 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertClosedLanes.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,9 @@ SOFTWARE. #pragma once #include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,35 +42,46 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ClosedLanes(const ClosedLanes_t& in, denm_msgs::ClosedLanes& out) { + if (in.innerhardShoulderStatus) { toRos_HardShoulderStatus(*in.innerhardShoulderStatus, out.innerhard_shoulder_status); out.innerhard_shoulder_status_is_present = true; } + if (in.outerhardShoulderStatus) { toRos_HardShoulderStatus(*in.outerhardShoulderStatus, out.outerhard_shoulder_status); out.outerhard_shoulder_status_is_present = true; } + if (in.drivingLaneStatus) { toRos_DrivingLaneStatus(*in.drivingLaneStatus, out.driving_lane_status); out.driving_lane_status_is_present = true; } + } void toStruct_ClosedLanes(const denm_msgs::ClosedLanes& in, ClosedLanes_t& out) { + memset(&out, 0, sizeof(ClosedLanes_t)); if (in.innerhard_shoulder_status_is_present) { - out.innerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); - toStruct_HardShoulderStatus(in.innerhard_shoulder_status, *out.innerhardShoulderStatus); + HardShoulderStatus_t innerhard_shoulder_status; + toStruct_HardShoulderStatus(in.innerhard_shoulder_status, innerhard_shoulder_status); + out.innerhardShoulderStatus = new HardShoulderStatus_t(innerhard_shoulder_status); } + if (in.outerhard_shoulder_status_is_present) { - out.outerhardShoulderStatus = (HardShoulderStatus_t*) calloc(1, sizeof(HardShoulderStatus_t)); - toStruct_HardShoulderStatus(in.outerhard_shoulder_status, *out.outerhardShoulderStatus); + HardShoulderStatus_t outerhard_shoulder_status; + toStruct_HardShoulderStatus(in.outerhard_shoulder_status, outerhard_shoulder_status); + out.outerhardShoulderStatus = new HardShoulderStatus_t(outerhard_shoulder_status); } + if (in.driving_lane_status_is_present) { - out.drivingLaneStatus = (DrivingLaneStatus_t*) calloc(1, sizeof(DrivingLaneStatus_t)); - toStruct_DrivingLaneStatus(in.driving_lane_status, *out.drivingLaneStatus); + DrivingLaneStatus_t driving_lane_status; + toStruct_DrivingLaneStatus(in.driving_lane_status, driving_lane_status); + out.drivingLaneStatus = new DrivingLaneStatus_t(driving_lane_status); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h index 16a98951c..7903cc748 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCollisionRiskSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CollisionRiskSubCauseCode(const CollisionRiskSubCauseCode_t& in, denm_msgs::CollisionRiskSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CollisionRiskSubCauseCode(const denm_msgs::CollisionRiskSubCauseCode& in, CollisionRiskSubCauseCode_t& out) { - memset(&out, 0, sizeof(CollisionRiskSubCauseCode_t)); + memset(&out, 0, sizeof(CollisionRiskSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h index a1923c1d9..15ca78d64 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvature.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Curvature(const Curvature_t& in, denm_msgs::Curvature& out) { + toRos_CurvatureValue(in.curvatureValue, out.curvature_value); toRos_CurvatureConfidence(in.curvatureConfidence, out.curvature_confidence); } void toStruct_Curvature(const denm_msgs::Curvature& in, Curvature_t& out) { + memset(&out, 0, sizeof(Curvature_t)); toStruct_CurvatureValue(in.curvature_value, out.curvatureValue); toStruct_CurvatureConfidence(in.curvature_confidence, out.curvatureConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h index 2dae5e459..8a4d41270 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureCalculationMode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CurvatureCalculationMode(const CurvatureCalculationMode_t& in, denm_msgs::CurvatureCalculationMode& out) { + out.value = in; } void toStruct_CurvatureCalculationMode(const denm_msgs::CurvatureCalculationMode& in, CurvatureCalculationMode_t& out) { - memset(&out, 0, sizeof(CurvatureCalculationMode_t)); + memset(&out, 0, sizeof(CurvatureCalculationMode_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h index 2ceda877e..b9e8f1b42 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CurvatureConfidence(const CurvatureConfidence_t& in, denm_msgs::CurvatureConfidence& out) { + out.value = in; } void toStruct_CurvatureConfidence(const denm_msgs::CurvatureConfidence& in, CurvatureConfidence_t& out) { - memset(&out, 0, sizeof(CurvatureConfidence_t)); + memset(&out, 0, sizeof(CurvatureConfidence_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h index 4105bf314..731b27d43 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertCurvatureValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_CurvatureValue(const CurvatureValue_t& in, denm_msgs::CurvatureValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_CurvatureValue(const denm_msgs::CurvatureValue& in, CurvatureValue_t& out) { - memset(&out, 0, sizeof(CurvatureValue_t)); + memset(&out, 0, sizeof(CurvatureValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h index 2ef3f199b..5034c5af5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDENM.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DENM(const DENM_t& in, denm_msgs::DENM& out) { + toRos_ItsPduHeader(in.header, out.header); toRos_DecentralizedEnvironmentalNotificationMessage(in.denm, out.denm); } void toStruct_DENM(const denm_msgs::DENM& in, DENM_t& out) { + memset(&out, 0, sizeof(DENM_t)); toStruct_ItsPduHeader(in.header, out.header); toStruct_DecentralizedEnvironmentalNotificationMessage(in.denm, out.denm); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h index 24df0a6fd..297856458 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousEndOfQueueSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousEndOfQueueSubCauseCode(const DangerousEndOfQueueSubCauseCode_t& in, denm_msgs::DangerousEndOfQueueSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousEndOfQueueSubCauseCode(const denm_msgs::DangerousEndOfQueueSubCauseCode& in, DangerousEndOfQueueSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousEndOfQueueSubCauseCode_t)); + memset(&out, 0, sizeof(DangerousEndOfQueueSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h index 925703055..c589cb24e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsBasic.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousGoodsBasic(const DangerousGoodsBasic_t& in, denm_msgs::DangerousGoodsBasic& out) { + out.value = in; } void toStruct_DangerousGoodsBasic(const denm_msgs::DangerousGoodsBasic& in, DangerousGoodsBasic_t& out) { - memset(&out, 0, sizeof(DangerousGoodsBasic_t)); + memset(&out, 0, sizeof(DangerousGoodsBasic_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h index 2aaf2d28e..538f96fb9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousGoodsExtended.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,16 +27,14 @@ SOFTWARE. #pragma once #include -#include +#include +#include +#include +#include #include -#include #include -#include -#include -#include -#include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -50,6 +47,7 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, denm_msgs::DangerousGoodsExtended& out) { + toRos_DangerousGoodsBasic(in.dangerousGoodsType, out.dangerous_goods_type); etsi_its_primitives_conversion::toRos_INTEGER(in.unNumber, out.un_number); etsi_its_primitives_conversion::toRos_BOOLEAN(in.elevatedTemperature, out.elevated_temperature); @@ -59,17 +57,21 @@ void toRos_DangerousGoodsExtended(const DangerousGoodsExtended_t& in, denm_msgs: etsi_its_primitives_conversion::toRos_IA5String(*in.emergencyActionCode, out.emergency_action_code); out.emergency_action_code_is_present = true; } + if (in.phoneNumber) { toRos_PhoneNumber(*in.phoneNumber, out.phone_number); out.phone_number_is_present = true; } + if (in.companyName) { etsi_its_primitives_conversion::toRos_UTF8String(*in.companyName, out.company_name); out.company_name_is_present = true; } + } void toStruct_DangerousGoodsExtended(const denm_msgs::DangerousGoodsExtended& in, DangerousGoodsExtended_t& out) { + memset(&out, 0, sizeof(DangerousGoodsExtended_t)); toStruct_DangerousGoodsBasic(in.dangerous_goods_type, out.dangerousGoodsType); @@ -78,17 +80,23 @@ void toStruct_DangerousGoodsExtended(const denm_msgs::DangerousGoodsExtended& in etsi_its_primitives_conversion::toStruct_BOOLEAN(in.tunnels_restricted, out.tunnelsRestricted); etsi_its_primitives_conversion::toStruct_BOOLEAN(in.limited_quantity, out.limitedQuantity); if (in.emergency_action_code_is_present) { - out.emergencyActionCode = (IA5String_t*) calloc(1, sizeof(IA5String_t)); - etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, *out.emergencyActionCode); + IA5String_t emergency_action_code; + etsi_its_primitives_conversion::toStruct_IA5String(in.emergency_action_code, emergency_action_code); + out.emergencyActionCode = new IA5String_t(emergency_action_code); } + if (in.phone_number_is_present) { - out.phoneNumber = (PhoneNumber_t*) calloc(1, sizeof(PhoneNumber_t)); - toStruct_PhoneNumber(in.phone_number, *out.phoneNumber); + PhoneNumber_t phone_number; + toStruct_PhoneNumber(in.phone_number, phone_number); + out.phoneNumber = new PhoneNumber_t(phone_number); } + if (in.company_name_is_present) { - out.companyName = (UTF8String_t*) calloc(1, sizeof(UTF8String_t)); - etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, *out.companyName); + UTF8String_t company_name; + etsi_its_primitives_conversion::toStruct_UTF8String(in.company_name, company_name); + out.companyName = new UTF8String_t(company_name); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h index 534fc9da3..86bc33b99 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDangerousSituationSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DangerousSituationSubCauseCode(const DangerousSituationSubCauseCode_t& in, denm_msgs::DangerousSituationSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DangerousSituationSubCauseCode(const denm_msgs::DangerousSituationSubCauseCode& in, DangerousSituationSubCauseCode_t& out) { - memset(&out, 0, sizeof(DangerousSituationSubCauseCode_t)); + memset(&out, 0, sizeof(DangerousSituationSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h index f90a43e05..9c7d1a667 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDecentralizedEnvironmentalNotificationMessage.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,10 +27,10 @@ SOFTWARE. #pragma once #include -#include -#include #include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -44,37 +43,48 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DecentralizedEnvironmentalNotificationMessage(const DecentralizedEnvironmentalNotificationMessage_t& in, denm_msgs::DecentralizedEnvironmentalNotificationMessage& out) { + toRos_ManagementContainer(in.management, out.management); if (in.situation) { toRos_SituationContainer(*in.situation, out.situation); out.situation_is_present = true; } + if (in.location) { toRos_LocationContainer(*in.location, out.location); out.location_is_present = true; } + if (in.alacarte) { toRos_AlacarteContainer(*in.alacarte, out.alacarte); out.alacarte_is_present = true; } + } void toStruct_DecentralizedEnvironmentalNotificationMessage(const denm_msgs::DecentralizedEnvironmentalNotificationMessage& in, DecentralizedEnvironmentalNotificationMessage_t& out) { + memset(&out, 0, sizeof(DecentralizedEnvironmentalNotificationMessage_t)); toStruct_ManagementContainer(in.management, out.management); if (in.situation_is_present) { - out.situation = (SituationContainer_t*) calloc(1, sizeof(SituationContainer_t)); - toStruct_SituationContainer(in.situation, *out.situation); + SituationContainer_t situation; + toStruct_SituationContainer(in.situation, situation); + out.situation = new SituationContainer_t(situation); } + if (in.location_is_present) { - out.location = (LocationContainer_t*) calloc(1, sizeof(LocationContainer_t)); - toStruct_LocationContainer(in.location, *out.location); + LocationContainer_t location; + toStruct_LocationContainer(in.location, location); + out.location = new LocationContainer_t(location); } + if (in.alacarte_is_present) { - out.alacarte = (AlacarteContainer_t*) calloc(1, sizeof(AlacarteContainer_t)); - toStruct_AlacarteContainer(in.alacarte, *out.alacarte); + AlacarteContainer_t alacarte; + toStruct_AlacarteContainer(in.alacarte, alacarte); + out.alacarte = new AlacarteContainer_t(alacarte); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h index 80b740f0a..260939d4e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaAltitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaAltitude(const DeltaAltitude_t& in, denm_msgs::DeltaAltitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaAltitude(const denm_msgs::DeltaAltitude& in, DeltaAltitude_t& out) { - memset(&out, 0, sizeof(DeltaAltitude_t)); + memset(&out, 0, sizeof(DeltaAltitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h index 55a4d8d3a..c4c01b149 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLatitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaLatitude(const DeltaLatitude_t& in, denm_msgs::DeltaLatitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLatitude(const denm_msgs::DeltaLatitude& in, DeltaLatitude_t& out) { - memset(&out, 0, sizeof(DeltaLatitude_t)); + memset(&out, 0, sizeof(DeltaLatitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h index 9ae00b60f..599747fdf 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaLongitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaLongitude(const DeltaLongitude_t& in, denm_msgs::DeltaLongitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_DeltaLongitude(const denm_msgs::DeltaLongitude& in, DeltaLongitude_t& out) { - memset(&out, 0, sizeof(DeltaLongitude_t)); + memset(&out, 0, sizeof(DeltaLongitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h index dfdf2a5c7..46ffcfe24 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDeltaReferencePosition.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,9 @@ SOFTWARE. #pragma once #include -#include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -43,12 +42,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DeltaReferencePosition(const DeltaReferencePosition_t& in, denm_msgs::DeltaReferencePosition& out) { + toRos_DeltaLatitude(in.deltaLatitude, out.delta_latitude); toRos_DeltaLongitude(in.deltaLongitude, out.delta_longitude); toRos_DeltaAltitude(in.deltaAltitude, out.delta_altitude); } void toStruct_DeltaReferencePosition(const denm_msgs::DeltaReferencePosition& in, DeltaReferencePosition_t& out) { + memset(&out, 0, sizeof(DeltaReferencePosition_t)); toStruct_DeltaLatitude(in.delta_latitude, out.deltaLatitude); @@ -56,4 +57,4 @@ void toStruct_DeltaReferencePosition(const denm_msgs::DeltaReferencePosition& in toStruct_DeltaAltitude(in.delta_altitude, out.deltaAltitude); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h index 3ff0107d2..ac3bc24e0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDigitalMap.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DigitalMap(const DigitalMap_t& in, denm_msgs::DigitalMap& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::ReferencePosition el; - toRos_ReferencePosition(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::ReferencePosition array; + toRos_ReferencePosition(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_DigitalMap(const denm_msgs::DigitalMap& in, DigitalMap_t& out) { + memset(&out, 0, sizeof(DigitalMap_t)); - for (int i = 0; i < in.array.size(); ++i) { - ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); - toStruct_ReferencePosition(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ReferencePosition_t array; + toStruct_ReferencePosition(in.array[i], array); + ReferencePosition_t* array_ptr = new ReferencePosition_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h index 03aa43dca..fcedc7180 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDriveDirection.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DriveDirection(const DriveDirection_t& in, denm_msgs::DriveDirection& out) { + out.value = in; } void toStruct_DriveDirection(const denm_msgs::DriveDirection& in, DriveDirection_t& out) { - memset(&out, 0, sizeof(DriveDirection_t)); + memset(&out, 0, sizeof(DriveDirection_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h index b22b025ce..6770f0af0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertDrivingLaneStatus.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_DrivingLaneStatus(const DrivingLaneStatus_t& in, denm_msgs::DrivingLaneStatus& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_DrivingLaneStatus(const denm_msgs::DrivingLaneStatus& in, DrivingLaneStatus_t& out) { - memset(&out, 0, sizeof(DrivingLaneStatus_t)); + memset(&out, 0, sizeof(DrivingLaneStatus_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h index cbe653daa..dbc333cd4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmbarkationStatus.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EmbarkationStatus(const EmbarkationStatus_t& in, denm_msgs::EmbarkationStatus& out) { + etsi_its_primitives_conversion::toRos_BOOLEAN(in, out.value); } void toStruct_EmbarkationStatus(const denm_msgs::EmbarkationStatus& in, EmbarkationStatus_t& out) { - memset(&out, 0, sizeof(EmbarkationStatus_t)); + memset(&out, 0, sizeof(EmbarkationStatus_t)); etsi_its_primitives_conversion::toStruct_BOOLEAN(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h index f72a36154..8839534af 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyPriority.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EmergencyPriority(const EmergencyPriority_t& in, denm_msgs::EmergencyPriority& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EmergencyPriority(const denm_msgs::EmergencyPriority& in, EmergencyPriority_t& out) { - memset(&out, 0, sizeof(EmergencyPriority_t)); + memset(&out, 0, sizeof(EmergencyPriority_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h index abc9966b0..4e500cd84 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEmergencyVehicleApproachingSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EmergencyVehicleApproachingSubCauseCode(const EmergencyVehicleApproachingSubCauseCode_t& in, denm_msgs::EmergencyVehicleApproachingSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_EmergencyVehicleApproachingSubCauseCode(const denm_msgs::EmergencyVehicleApproachingSubCauseCode& in, EmergencyVehicleApproachingSubCauseCode_t& out) { - memset(&out, 0, sizeof(EmergencyVehicleApproachingSubCauseCode_t)); + memset(&out, 0, sizeof(EmergencyVehicleApproachingSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h index 0237f49b4..c292d395a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEnergyStorageType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EnergyStorageType(const EnergyStorageType_t& in, denm_msgs::EnergyStorageType& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_EnergyStorageType(const denm_msgs::EnergyStorageType& in, EnergyStorageType_t& out) { - memset(&out, 0, sizeof(EnergyStorageType_t)); + memset(&out, 0, sizeof(EnergyStorageType_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h index 7fa8b2bc6..2ffbc6a15 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventHistory.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EventHistory(const EventHistory_t& in, denm_msgs::EventHistory& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::EventPoint el; - toRos_EventPoint(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::EventPoint array; + toRos_EventPoint(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_EventHistory(const denm_msgs::EventHistory& in, EventHistory_t& out) { + memset(&out, 0, sizeof(EventHistory_t)); - for (int i = 0; i < in.array.size(); ++i) { - EventPoint_t* el = (EventPoint_t*) calloc(1, sizeof(EventPoint_t)); - toStruct_EventPoint(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + EventPoint_t array; + toStruct_EventPoint(in.array[i], array); + EventPoint_t* array_ptr = new EventPoint_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h index 95e956aaa..1904017d1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertEventPoint.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,8 +28,8 @@ SOFTWARE. #include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -43,23 +42,28 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_EventPoint(const EventPoint_t& in, denm_msgs::EventPoint& out) { + toRos_DeltaReferencePosition(in.eventPosition, out.event_position); if (in.eventDeltaTime) { toRos_PathDeltaTime(*in.eventDeltaTime, out.event_delta_time); out.event_delta_time_is_present = true; } + toRos_InformationQuality(in.informationQuality, out.information_quality); } void toStruct_EventPoint(const denm_msgs::EventPoint& in, EventPoint_t& out) { + memset(&out, 0, sizeof(EventPoint_t)); toStruct_DeltaReferencePosition(in.event_position, out.eventPosition); if (in.event_delta_time_is_present) { - out.eventDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); - toStruct_PathDeltaTime(in.event_delta_time, *out.eventDeltaTime); + PathDeltaTime_t event_delta_time; + toStruct_PathDeltaTime(in.event_delta_time, event_delta_time); + out.eventDeltaTime = new PathDeltaTime_t(event_delta_time); } + toStruct_InformationQuality(in.information_quality, out.informationQuality); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h index a56ad554f..58a098d73 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertExteriorLights.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ExteriorLights(const ExteriorLights_t& in, denm_msgs::ExteriorLights& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_ExteriorLights(const denm_msgs::ExteriorLights& in, ExteriorLights_t& out) { - memset(&out, 0, sizeof(ExteriorLights_t)); + memset(&out, 0, sizeof(ExteriorLights_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h index 1e21c3061..1fcdeb4ad 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHardShoulderStatus.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HardShoulderStatus(const HardShoulderStatus_t& in, denm_msgs::HardShoulderStatus& out) { + out.value = in; } void toStruct_HardShoulderStatus(const denm_msgs::HardShoulderStatus& in, HardShoulderStatus_t& out) { - memset(&out, 0, sizeof(HardShoulderStatus_t)); + memset(&out, 0, sizeof(HardShoulderStatus_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h index 5ca824213..964b4afce 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationAnimalOnTheRoadSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationAnimalOnTheRoadSubCauseCode(const HazardousLocation_AnimalOnTheRoadSubCauseCode_t& in, denm_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationAnimalOnTheRoadSubCauseCode(const denm_msgs::HazardousLocationAnimalOnTheRoadSubCauseCode& in, HazardousLocation_AnimalOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_AnimalOnTheRoadSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_AnimalOnTheRoadSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h index ef82abeea..47a672896 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationDangerousCurveSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationDangerousCurveSubCauseCode(const HazardousLocation_DangerousCurveSubCauseCode_t& in, denm_msgs::HazardousLocationDangerousCurveSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationDangerousCurveSubCauseCode(const denm_msgs::HazardousLocationDangerousCurveSubCauseCode& in, HazardousLocation_DangerousCurveSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_DangerousCurveSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_DangerousCurveSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h index 124c43bfb..38fd6dccc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationObstacleOnTheRoadSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationObstacleOnTheRoadSubCauseCode(const HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& in, denm_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationObstacleOnTheRoadSubCauseCode(const denm_msgs::HazardousLocationObstacleOnTheRoadSubCauseCode& in, HazardousLocation_ObstacleOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_ObstacleOnTheRoadSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_ObstacleOnTheRoadSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h index be0a55e58..d91d2697b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHazardousLocationSurfaceConditionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HazardousLocationSurfaceConditionSubCauseCode(const HazardousLocation_SurfaceConditionSubCauseCode_t& in, denm_msgs::HazardousLocationSurfaceConditionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HazardousLocationSurfaceConditionSubCauseCode(const denm_msgs::HazardousLocationSurfaceConditionSubCauseCode& in, HazardousLocation_SurfaceConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(HazardousLocation_SurfaceConditionSubCauseCode_t)); + memset(&out, 0, sizeof(HazardousLocation_SurfaceConditionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h index 6dc709dbb..6005aa926 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeading.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Heading(const Heading_t& in, denm_msgs::Heading& out) { + toRos_HeadingValue(in.headingValue, out.heading_value); toRos_HeadingConfidence(in.headingConfidence, out.heading_confidence); } void toStruct_Heading(const denm_msgs::Heading& in, Heading_t& out) { + memset(&out, 0, sizeof(Heading_t)); toStruct_HeadingValue(in.heading_value, out.headingValue); toStruct_HeadingConfidence(in.heading_confidence, out.headingConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h index 49581d239..22acd9eca 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HeadingConfidence(const HeadingConfidence_t& in, denm_msgs::HeadingConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingConfidence(const denm_msgs::HeadingConfidence& in, HeadingConfidence_t& out) { - memset(&out, 0, sizeof(HeadingConfidence_t)); + memset(&out, 0, sizeof(HeadingConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h index 5014bed18..4e4cc190e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeadingValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HeadingValue(const HeadingValue_t& in, denm_msgs::HeadingValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeadingValue(const denm_msgs::HeadingValue& in, HeadingValue_t& out) { - memset(&out, 0, sizeof(HeadingValue_t)); + memset(&out, 0, sizeof(HeadingValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h index 3c014cd18..ab6f250d9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHeightLonCarr.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HeightLonCarr(const HeightLonCarr_t& in, denm_msgs::HeightLonCarr& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HeightLonCarr(const denm_msgs::HeightLonCarr& in, HeightLonCarr_t& out) { - memset(&out, 0, sizeof(HeightLonCarr_t)); + memset(&out, 0, sizeof(HeightLonCarr_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h index aa92d554a..fb249336c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanPresenceOnTheRoadSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HumanPresenceOnTheRoadSubCauseCode(const HumanPresenceOnTheRoadSubCauseCode_t& in, denm_msgs::HumanPresenceOnTheRoadSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanPresenceOnTheRoadSubCauseCode(const denm_msgs::HumanPresenceOnTheRoadSubCauseCode& in, HumanPresenceOnTheRoadSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanPresenceOnTheRoadSubCauseCode_t)); + memset(&out, 0, sizeof(HumanPresenceOnTheRoadSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h index e3cff2980..dee227fa5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertHumanProblemSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_HumanProblemSubCauseCode(const HumanProblemSubCauseCode_t& in, denm_msgs::HumanProblemSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_HumanProblemSubCauseCode(const denm_msgs::HumanProblemSubCauseCode& in, HumanProblemSubCauseCode_t& out) { - memset(&out, 0, sizeof(HumanProblemSubCauseCode_t)); + memset(&out, 0, sizeof(HumanProblemSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h index d06368c72..a99073bb9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertImpactReductionContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,15 +28,17 @@ SOFTWARE. #include #include -#include -#include +#include +#include #include -#include #include -#include +#include +#include #include +#include +#include #include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -50,6 +51,7 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ImpactReductionContainer(const ImpactReductionContainer_t& in, denm_msgs::ImpactReductionContainer& out) { + toRos_HeightLonCarr(in.heightLonCarrLeft, out.height_lon_carr_left); toRos_HeightLonCarr(in.heightLonCarrRight, out.height_lon_carr_right); toRos_PosLonCarr(in.posLonCarrLeft, out.pos_lon_carr_left); @@ -65,6 +67,7 @@ void toRos_ImpactReductionContainer(const ImpactReductionContainer_t& in, denm_m } void toStruct_ImpactReductionContainer(const denm_msgs::ImpactReductionContainer& in, ImpactReductionContainer_t& out) { + memset(&out, 0, sizeof(ImpactReductionContainer_t)); toStruct_HeightLonCarr(in.height_lon_carr_left, out.heightLonCarrLeft); @@ -81,4 +84,4 @@ void toStruct_ImpactReductionContainer(const denm_msgs::ImpactReductionContainer toStruct_RequestResponseIndication(in.request_response_indication, out.requestResponseIndication); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h index dea5de12f..76fb0dc8c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertInformationQuality.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_InformationQuality(const InformationQuality_t& in, denm_msgs::InformationQuality& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_InformationQuality(const denm_msgs::InformationQuality& in, InformationQuality_t& out) { - memset(&out, 0, sizeof(InformationQuality_t)); + memset(&out, 0, sizeof(InformationQuality_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h index 588aeac0a..ed2ea6522 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItineraryPath.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ItineraryPath(const ItineraryPath_t& in, denm_msgs::ItineraryPath& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::ReferencePosition el; - toRos_ReferencePosition(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::ReferencePosition array; + toRos_ReferencePosition(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_ItineraryPath(const denm_msgs::ItineraryPath& in, ItineraryPath_t& out) { + memset(&out, 0, sizeof(ItineraryPath_t)); - for (int i = 0; i < in.array.size(); ++i) { - ReferencePosition_t* el = (ReferencePosition_t*) calloc(1, sizeof(ReferencePosition_t)); - toStruct_ReferencePosition(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ReferencePosition_t array; + toStruct_ReferencePosition(in.array[i], array); + ReferencePosition_t* array_ptr = new ReferencePosition_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h index 4acd87379..fc8e24709 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertItsPduHeader.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,7 @@ SOFTWARE. #pragma once #include -#include +#include #include #include #ifdef ROS1 @@ -43,12 +42,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ItsPduHeader(const ItsPduHeader_t& in, denm_msgs::ItsPduHeader& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in.protocolVersion, out.protocol_version); etsi_its_primitives_conversion::toRos_INTEGER(in.messageID, out.message_id); toRos_StationID(in.stationID, out.station_id); } void toStruct_ItsPduHeader(const denm_msgs::ItsPduHeader& in, ItsPduHeader_t& out) { + memset(&out, 0, sizeof(ItsPduHeader_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.protocol_version, out.protocolVersion); @@ -56,4 +57,4 @@ void toStruct_ItsPduHeader(const denm_msgs::ItsPduHeader& in, ItsPduHeader_t& ou toStruct_StationID(in.station_id, out.stationID); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h index a0b4d8796..4f6dd7b30 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLanePosition.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LanePosition(const LanePosition_t& in, denm_msgs::LanePosition& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LanePosition(const denm_msgs::LanePosition& in, LanePosition_t& out) { - memset(&out, 0, sizeof(LanePosition_t)); + memset(&out, 0, sizeof(LanePosition_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h index b2d137132..bf49dc0c0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAcceleration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LateralAcceleration(const LateralAcceleration_t& in, denm_msgs::LateralAcceleration& out) { + toRos_LateralAccelerationValue(in.lateralAccelerationValue, out.lateral_acceleration_value); toRos_AccelerationConfidence(in.lateralAccelerationConfidence, out.lateral_acceleration_confidence); } void toStruct_LateralAcceleration(const denm_msgs::LateralAcceleration& in, LateralAcceleration_t& out) { + memset(&out, 0, sizeof(LateralAcceleration_t)); toStruct_LateralAccelerationValue(in.lateral_acceleration_value, out.lateralAccelerationValue); toStruct_AccelerationConfidence(in.lateral_acceleration_confidence, out.lateralAccelerationConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h index b30cf6bfc..8c13da0e1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLateralAccelerationValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LateralAccelerationValue(const LateralAccelerationValue_t& in, denm_msgs::LateralAccelerationValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LateralAccelerationValue(const denm_msgs::LateralAccelerationValue& in, LateralAccelerationValue_t& out) { - memset(&out, 0, sizeof(LateralAccelerationValue_t)); + memset(&out, 0, sizeof(LateralAccelerationValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h index 06d959573..62e7d34e9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLatitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Latitude(const Latitude_t& in, denm_msgs::Latitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Latitude(const denm_msgs::Latitude& in, Latitude_t& out) { - memset(&out, 0, sizeof(Latitude_t)); + memset(&out, 0, sizeof(Latitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h index b471d7692..fe29a5da9 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLightBarSirenInUse.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LightBarSirenInUse(const LightBarSirenInUse_t& in, denm_msgs::LightBarSirenInUse& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_LightBarSirenInUse(const denm_msgs::LightBarSirenInUse& in, LightBarSirenInUse_t& out) { - memset(&out, 0, sizeof(LightBarSirenInUse_t)); + memset(&out, 0, sizeof(LightBarSirenInUse_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h index 204738acd..e9fce0141 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLocationContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,10 +27,10 @@ SOFTWARE. #pragma once #include -#include -#include #include +#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -44,37 +43,48 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LocationContainer(const LocationContainer_t& in, denm_msgs::LocationContainer& out) { + if (in.eventSpeed) { toRos_Speed(*in.eventSpeed, out.event_speed); out.event_speed_is_present = true; } + if (in.eventPositionHeading) { toRos_Heading(*in.eventPositionHeading, out.event_position_heading); out.event_position_heading_is_present = true; } + toRos_Traces(in.traces, out.traces); if (in.roadType) { toRos_RoadType(*in.roadType, out.road_type); out.road_type_is_present = true; } + } void toStruct_LocationContainer(const denm_msgs::LocationContainer& in, LocationContainer_t& out) { + memset(&out, 0, sizeof(LocationContainer_t)); if (in.event_speed_is_present) { - out.eventSpeed = (Speed_t*) calloc(1, sizeof(Speed_t)); - toStruct_Speed(in.event_speed, *out.eventSpeed); + Speed_t event_speed; + toStruct_Speed(in.event_speed, event_speed); + out.eventSpeed = new Speed_t(event_speed); } + if (in.event_position_heading_is_present) { - out.eventPositionHeading = (Heading_t*) calloc(1, sizeof(Heading_t)); - toStruct_Heading(in.event_position_heading, *out.eventPositionHeading); + Heading_t event_position_heading; + toStruct_Heading(in.event_position_heading, event_position_heading); + out.eventPositionHeading = new Heading_t(event_position_heading); } + toStruct_Traces(in.traces, out.traces); if (in.road_type_is_present) { - out.roadType = (RoadType_t*) calloc(1, sizeof(RoadType_t)); - toStruct_RoadType(in.road_type, *out.roadType); + RoadType_t road_type; + toStruct_RoadType(in.road_type, road_type); + out.roadType = new RoadType_t(road_type); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h index 85565e8c2..e87557abc 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitude.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Longitude(const Longitude_t& in, denm_msgs::Longitude& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Longitude(const denm_msgs::Longitude& in, Longitude_t& out) { - memset(&out, 0, sizeof(Longitude_t)); + memset(&out, 0, sizeof(Longitude_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h index 493f16207..9a7a64174 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAcceleration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LongitudinalAcceleration(const LongitudinalAcceleration_t& in, denm_msgs::LongitudinalAcceleration& out) { + toRos_LongitudinalAccelerationValue(in.longitudinalAccelerationValue, out.longitudinal_acceleration_value); toRos_AccelerationConfidence(in.longitudinalAccelerationConfidence, out.longitudinal_acceleration_confidence); } void toStruct_LongitudinalAcceleration(const denm_msgs::LongitudinalAcceleration& in, LongitudinalAcceleration_t& out) { + memset(&out, 0, sizeof(LongitudinalAcceleration_t)); toStruct_LongitudinalAccelerationValue(in.longitudinal_acceleration_value, out.longitudinalAccelerationValue); toStruct_AccelerationConfidence(in.longitudinal_acceleration_confidence, out.longitudinalAccelerationConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h index a24bf9aa4..ad1a820be 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertLongitudinalAccelerationValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_LongitudinalAccelerationValue(const LongitudinalAccelerationValue_t& in, denm_msgs::LongitudinalAccelerationValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_LongitudinalAccelerationValue(const denm_msgs::LongitudinalAccelerationValue& in, LongitudinalAccelerationValue_t& out) { - memset(&out, 0, sizeof(LongitudinalAccelerationValue_t)); + memset(&out, 0, sizeof(LongitudinalAccelerationValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h index 75f1facd4..6b6687623 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertManagementContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,14 +28,15 @@ SOFTWARE. #include #include +#include +#include +#include #include #include #include -#include -#include -#include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -49,6 +49,7 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ManagementContainer(const ManagementContainer_t& in, denm_msgs::ManagementContainer& out) { + toRos_ActionID(in.actionID, out.action_id); toRos_TimestampIts(in.detectionTime, out.detection_time); toRos_TimestampIts(in.referenceTime, out.reference_time); @@ -56,51 +57,67 @@ void toRos_ManagementContainer(const ManagementContainer_t& in, denm_msgs::Manag toRos_Termination(*in.termination, out.termination); out.termination_is_present = true; } + toRos_ReferencePosition(in.eventPosition, out.event_position); if (in.relevanceDistance) { toRos_RelevanceDistance(*in.relevanceDistance, out.relevance_distance); out.relevance_distance_is_present = true; } + if (in.relevanceTrafficDirection) { toRos_RelevanceTrafficDirection(*in.relevanceTrafficDirection, out.relevance_traffic_direction); out.relevance_traffic_direction_is_present = true; } + if (in.validityDuration) { toRos_ValidityDuration(*in.validityDuration, out.validity_duration); } + if (in.transmissionInterval) { toRos_TransmissionInterval(*in.transmissionInterval, out.transmission_interval); out.transmission_interval_is_present = true; } + toRos_StationType(in.stationType, out.station_type); } void toStruct_ManagementContainer(const denm_msgs::ManagementContainer& in, ManagementContainer_t& out) { + memset(&out, 0, sizeof(ManagementContainer_t)); toStruct_ActionID(in.action_id, out.actionID); toStruct_TimestampIts(in.detection_time, out.detectionTime); toStruct_TimestampIts(in.reference_time, out.referenceTime); if (in.termination_is_present) { - out.termination = (Termination_t*) calloc(1, sizeof(Termination_t)); - toStruct_Termination(in.termination, *out.termination); + Termination_t termination; + toStruct_Termination(in.termination, termination); + out.termination = new Termination_t(termination); } + toStruct_ReferencePosition(in.event_position, out.eventPosition); if (in.relevance_distance_is_present) { - out.relevanceDistance = (RelevanceDistance_t*) calloc(1, sizeof(RelevanceDistance_t)); - toStruct_RelevanceDistance(in.relevance_distance, *out.relevanceDistance); + RelevanceDistance_t relevance_distance; + toStruct_RelevanceDistance(in.relevance_distance, relevance_distance); + out.relevanceDistance = new RelevanceDistance_t(relevance_distance); } + if (in.relevance_traffic_direction_is_present) { - out.relevanceTrafficDirection = (RelevanceTrafficDirection_t*) calloc(1, sizeof(RelevanceTrafficDirection_t)); - toStruct_RelevanceTrafficDirection(in.relevance_traffic_direction, *out.relevanceTrafficDirection); + RelevanceTrafficDirection_t relevance_traffic_direction; + toStruct_RelevanceTrafficDirection(in.relevance_traffic_direction, relevance_traffic_direction); + out.relevanceTrafficDirection = new RelevanceTrafficDirection_t(relevance_traffic_direction); } - out.validityDuration = (ValidityDuration_t*) calloc(1, sizeof(ValidityDuration_t)); - toStruct_ValidityDuration(in.validity_duration, *out.validityDuration); + + ValidityDuration_t validity_duration; + toStruct_ValidityDuration(in.validity_duration, validity_duration); + out.validityDuration = new ValidityDuration_t(validity_duration); + if (in.transmission_interval_is_present) { - out.transmissionInterval = (TransmissionInterval_t*) calloc(1, sizeof(TransmissionInterval_t)); - toStruct_TransmissionInterval(in.transmission_interval, *out.transmissionInterval); + TransmissionInterval_t transmission_interval; + toStruct_TransmissionInterval(in.transmission_interval, transmission_interval); + out.transmissionInterval = new TransmissionInterval_t(transmission_interval); } + toStruct_StationType(in.station_type, out.stationType); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h index 3f0170ba2..b693932c2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertNumberOfOccupants.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_NumberOfOccupants(const NumberOfOccupants_t& in, denm_msgs::NumberOfOccupants& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_NumberOfOccupants(const denm_msgs::NumberOfOccupants& in, NumberOfOccupants_t& out) { - memset(&out, 0, sizeof(NumberOfOccupants_t)); + memset(&out, 0, sizeof(NumberOfOccupants_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h index b8eb82f15..1aab4e75d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertOpeningDaysHours.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_OpeningDaysHours(const OpeningDaysHours_t& in, denm_msgs::OpeningDaysHours& out) { + etsi_its_primitives_conversion::toRos_UTF8String(in, out.value); } void toStruct_OpeningDaysHours(const denm_msgs::OpeningDaysHours& in, OpeningDaysHours_t& out) { - memset(&out, 0, sizeof(OpeningDaysHours_t)); + memset(&out, 0, sizeof(OpeningDaysHours_t)); etsi_its_primitives_conversion::toStruct_UTF8String(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h index df8a582ef..e3f921a51 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathDeltaTime.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PathDeltaTime(const PathDeltaTime_t& in, denm_msgs::PathDeltaTime& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PathDeltaTime(const denm_msgs::PathDeltaTime& in, PathDeltaTime_t& out) { - memset(&out, 0, sizeof(PathDeltaTime_t)); + memset(&out, 0, sizeof(PathDeltaTime_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h index e88eb707f..059c06ba7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathHistory.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PathHistory(const PathHistory_t& in, denm_msgs::PathHistory& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::PathPoint el; - toRos_PathPoint(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::PathPoint array; + toRos_PathPoint(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_PathHistory(const denm_msgs::PathHistory& in, PathHistory_t& out) { + memset(&out, 0, sizeof(PathHistory_t)); - for (int i = 0; i < in.array.size(); ++i) { - PathPoint_t* el = (PathPoint_t*) calloc(1, sizeof(PathPoint_t)); - toStruct_PathPoint(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + PathPoint_t array; + toStruct_PathPoint(in.array[i], array); + PathPoint_t* array_ptr = new PathPoint_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h index 68f19c330..d6f6f2b8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPathPoint.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,21 +41,26 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PathPoint(const PathPoint_t& in, denm_msgs::PathPoint& out) { + toRos_DeltaReferencePosition(in.pathPosition, out.path_position); if (in.pathDeltaTime) { toRos_PathDeltaTime(*in.pathDeltaTime, out.path_delta_time); out.path_delta_time_is_present = true; } + } void toStruct_PathPoint(const denm_msgs::PathPoint& in, PathPoint_t& out) { + memset(&out, 0, sizeof(PathPoint_t)); toStruct_DeltaReferencePosition(in.path_position, out.pathPosition); if (in.path_delta_time_is_present) { - out.pathDeltaTime = (PathDeltaTime_t*) calloc(1, sizeof(PathDeltaTime_t)); - toStruct_PathDeltaTime(in.path_delta_time, *out.pathDeltaTime); + PathDeltaTime_t path_delta_time; + toStruct_PathDeltaTime(in.path_delta_time, path_delta_time); + out.pathDeltaTime = new PathDeltaTime_t(path_delta_time); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h index b05653501..51b3e6dd4 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPerformanceClass.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PerformanceClass(const PerformanceClass_t& in, denm_msgs::PerformanceClass& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PerformanceClass(const denm_msgs::PerformanceClass& in, PerformanceClass_t& out) { - memset(&out, 0, sizeof(PerformanceClass_t)); + memset(&out, 0, sizeof(PerformanceClass_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h index 142620965..a77882ea0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPhoneNumber.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PhoneNumber(const PhoneNumber_t& in, denm_msgs::PhoneNumber& out) { + etsi_its_primitives_conversion::toRos_NumericString(in, out.value); } void toStruct_PhoneNumber(const denm_msgs::PhoneNumber& in, PhoneNumber_t& out) { - memset(&out, 0, sizeof(PhoneNumber_t)); + memset(&out, 0, sizeof(PhoneNumber_t)); etsi_its_primitives_conversion::toStruct_NumericString(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h index 001c472c9..54ce41e9d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosCentMass.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosCentMass(const PosCentMass_t& in, denm_msgs::PosCentMass& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosCentMass(const denm_msgs::PosCentMass& in, PosCentMass_t& out) { - memset(&out, 0, sizeof(PosCentMass_t)); + memset(&out, 0, sizeof(PosCentMass_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h index 79c1a5b40..0ed2e6736 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosConfidenceEllipse.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,9 @@ SOFTWARE. #pragma once #include -#include #include +#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,12 +42,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosConfidenceEllipse(const PosConfidenceEllipse_t& in, denm_msgs::PosConfidenceEllipse& out) { + toRos_SemiAxisLength(in.semiMajorConfidence, out.semi_major_confidence); toRos_SemiAxisLength(in.semiMinorConfidence, out.semi_minor_confidence); toRos_HeadingValue(in.semiMajorOrientation, out.semi_major_orientation); } void toStruct_PosConfidenceEllipse(const denm_msgs::PosConfidenceEllipse& in, PosConfidenceEllipse_t& out) { + memset(&out, 0, sizeof(PosConfidenceEllipse_t)); toStruct_SemiAxisLength(in.semi_major_confidence, out.semiMajorConfidence); @@ -55,4 +57,4 @@ void toStruct_PosConfidenceEllipse(const denm_msgs::PosConfidenceEllipse& in, Po toStruct_HeadingValue(in.semi_major_orientation, out.semiMajorOrientation); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h index 89c371eaa..cceb58a82 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosFrontAx.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosFrontAx(const PosFrontAx_t& in, denm_msgs::PosFrontAx& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosFrontAx(const denm_msgs::PosFrontAx& in, PosFrontAx_t& out) { - memset(&out, 0, sizeof(PosFrontAx_t)); + memset(&out, 0, sizeof(PosFrontAx_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h index 5eb681743..f7c17bbcd 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosLonCarr.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosLonCarr(const PosLonCarr_t& in, denm_msgs::PosLonCarr& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosLonCarr(const denm_msgs::PosLonCarr& in, PosLonCarr_t& out) { - memset(&out, 0, sizeof(PosLonCarr_t)); + memset(&out, 0, sizeof(PosLonCarr_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h index 9f24dae9a..db3a63bed 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPosPillar.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PosPillar(const PosPillar_t& in, denm_msgs::PosPillar& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PosPillar(const denm_msgs::PosPillar& in, PosPillar_t& out) { - memset(&out, 0, sizeof(PosPillar_t)); + memset(&out, 0, sizeof(PosPillar_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h index 4ab5de1a5..27f26626a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfOccupants.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PositionOfOccupants(const PositionOfOccupants_t& in, denm_msgs::PositionOfOccupants& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_PositionOfOccupants(const denm_msgs::PositionOfOccupants& in, PositionOfOccupants_t& out) { - memset(&out, 0, sizeof(PositionOfOccupants_t)); + memset(&out, 0, sizeof(PositionOfOccupants_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h index 409ba950c..f91112aa1 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositionOfPillars.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PositionOfPillars(const PositionOfPillars_t& in, denm_msgs::PositionOfPillars& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::PosPillar el; - toRos_PosPillar(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::PosPillar array; + toRos_PosPillar(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_PositionOfPillars(const denm_msgs::PositionOfPillars& in, PositionOfPillars_t& out) { + memset(&out, 0, sizeof(PositionOfPillars_t)); - for (int i = 0; i < in.array.size(); ++i) { - PosPillar_t* el = (PosPillar_t*) calloc(1, sizeof(PosPillar_t)); - toStruct_PosPillar(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + PosPillar_t array; + toStruct_PosPillar(in.array[i], array); + PosPillar_t* array_ptr = new PosPillar_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h index 95696a013..a6a4428e2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPositioningSolutionType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PositioningSolutionType(const PositioningSolutionType_t& in, denm_msgs::PositioningSolutionType& out) { + out.value = in; } void toStruct_PositioningSolutionType(const denm_msgs::PositioningSolutionType& in, PositioningSolutionType_t& out) { - memset(&out, 0, sizeof(PositioningSolutionType_t)); + memset(&out, 0, sizeof(PositioningSolutionType_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h index f2388a51e..ace609eeb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPostCrashSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PostCrashSubCauseCode(const PostCrashSubCauseCode_t& in, denm_msgs::PostCrashSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PostCrashSubCauseCode(const denm_msgs::PostCrashSubCauseCode& in, PostCrashSubCauseCode_t& out) { - memset(&out, 0, sizeof(PostCrashSubCauseCode_t)); + memset(&out, 0, sizeof(PostCrashSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h index ec8188eef..04859a769 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZone.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,12 +27,12 @@ SOFTWARE. #pragma once #include +#include +#include #include #include -#include #include -#include -#include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -46,41 +45,52 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedCommunicationZone(const ProtectedCommunicationZone_t& in, denm_msgs::ProtectedCommunicationZone& out) { + toRos_ProtectedZoneType(in.protectedZoneType, out.protected_zone_type); if (in.expiryTime) { toRos_TimestampIts(*in.expiryTime, out.expiry_time); out.expiry_time_is_present = true; } + toRos_Latitude(in.protectedZoneLatitude, out.protected_zone_latitude); toRos_Longitude(in.protectedZoneLongitude, out.protected_zone_longitude); if (in.protectedZoneRadius) { toRos_ProtectedZoneRadius(*in.protectedZoneRadius, out.protected_zone_radius); out.protected_zone_radius_is_present = true; } + if (in.protectedZoneID) { toRos_ProtectedZoneID(*in.protectedZoneID, out.protected_zone_id); out.protected_zone_id_is_present = true; } + } void toStruct_ProtectedCommunicationZone(const denm_msgs::ProtectedCommunicationZone& in, ProtectedCommunicationZone_t& out) { + memset(&out, 0, sizeof(ProtectedCommunicationZone_t)); toStruct_ProtectedZoneType(in.protected_zone_type, out.protectedZoneType); if (in.expiry_time_is_present) { - out.expiryTime = (TimestampIts_t*) calloc(1, sizeof(TimestampIts_t)); - toStruct_TimestampIts(in.expiry_time, *out.expiryTime); + TimestampIts_t expiry_time; + toStruct_TimestampIts(in.expiry_time, expiry_time); + out.expiryTime = new TimestampIts_t(expiry_time); } + toStruct_Latitude(in.protected_zone_latitude, out.protectedZoneLatitude); toStruct_Longitude(in.protected_zone_longitude, out.protectedZoneLongitude); if (in.protected_zone_radius_is_present) { - out.protectedZoneRadius = (ProtectedZoneRadius_t*) calloc(1, sizeof(ProtectedZoneRadius_t)); - toStruct_ProtectedZoneRadius(in.protected_zone_radius, *out.protectedZoneRadius); + ProtectedZoneRadius_t protected_zone_radius; + toStruct_ProtectedZoneRadius(in.protected_zone_radius, protected_zone_radius); + out.protectedZoneRadius = new ProtectedZoneRadius_t(protected_zone_radius); } + if (in.protected_zone_id_is_present) { - out.protectedZoneID = (ProtectedZoneID_t*) calloc(1, sizeof(ProtectedZoneID_t)); - toStruct_ProtectedZoneID(in.protected_zone_id, *out.protectedZoneID); + ProtectedZoneID_t protected_zone_id; + toStruct_ProtectedZoneID(in.protected_zone_id, protected_zone_id); + out.protectedZoneID = new ProtectedZoneID_t(protected_zone_id); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h index 836b8e3ae..44b51e993 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedCommunicationZonesRSU.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedCommunicationZonesRSU(const ProtectedCommunicationZonesRSU_t& in, denm_msgs::ProtectedCommunicationZonesRSU& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::ProtectedCommunicationZone el; - toRos_ProtectedCommunicationZone(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::ProtectedCommunicationZone array; + toRos_ProtectedCommunicationZone(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_ProtectedCommunicationZonesRSU(const denm_msgs::ProtectedCommunicationZonesRSU& in, ProtectedCommunicationZonesRSU_t& out) { + memset(&out, 0, sizeof(ProtectedCommunicationZonesRSU_t)); - for (int i = 0; i < in.array.size(); ++i) { - ProtectedCommunicationZone_t* el = (ProtectedCommunicationZone_t*) calloc(1, sizeof(ProtectedCommunicationZone_t)); - toStruct_ProtectedCommunicationZone(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ProtectedCommunicationZone_t array; + toStruct_ProtectedCommunicationZone(in.array[i], array); + ProtectedCommunicationZone_t* array_ptr = new ProtectedCommunicationZone_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h index 510d52e00..9e16ae02e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedZoneID(const ProtectedZoneID_t& in, denm_msgs::ProtectedZoneID& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneID(const denm_msgs::ProtectedZoneID& in, ProtectedZoneID_t& out) { - memset(&out, 0, sizeof(ProtectedZoneID_t)); + memset(&out, 0, sizeof(ProtectedZoneID_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h index 817a26390..8b70322a0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneRadius.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedZoneRadius(const ProtectedZoneRadius_t& in, denm_msgs::ProtectedZoneRadius& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ProtectedZoneRadius(const denm_msgs::ProtectedZoneRadius& in, ProtectedZoneRadius_t& out) { - memset(&out, 0, sizeof(ProtectedZoneRadius_t)); + memset(&out, 0, sizeof(ProtectedZoneRadius_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h index cfd7239a4..8d88b9532 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertProtectedZoneType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ProtectedZoneType(const ProtectedZoneType_t& in, denm_msgs::ProtectedZoneType& out) { + out.value = in; } void toStruct_ProtectedZoneType(const denm_msgs::ProtectedZoneType& in, ProtectedZoneType_t& out) { - memset(&out, 0, sizeof(ProtectedZoneType_t)); + memset(&out, 0, sizeof(ProtectedZoneType_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h index 6ffff2422..e1e19687b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivation.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PtActivation(const PtActivation_t& in, denm_msgs::PtActivation& out) { + toRos_PtActivationType(in.ptActivationType, out.pt_activation_type); toRos_PtActivationData(in.ptActivationData, out.pt_activation_data); } void toStruct_PtActivation(const denm_msgs::PtActivation& in, PtActivation_t& out) { + memset(&out, 0, sizeof(PtActivation_t)); toStruct_PtActivationType(in.pt_activation_type, out.ptActivationType); toStruct_PtActivationData(in.pt_activation_data, out.ptActivationData); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h index 40412b152..8620cac77 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationData.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PtActivationData(const PtActivationData_t& in, denm_msgs::PtActivationData& out) { + etsi_its_primitives_conversion::toRos_OCTET_STRING(in, out.value); } void toStruct_PtActivationData(const denm_msgs::PtActivationData& in, PtActivationData_t& out) { - memset(&out, 0, sizeof(PtActivationData_t)); + memset(&out, 0, sizeof(PtActivationData_t)); etsi_its_primitives_conversion::toStruct_OCTET_STRING(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h index 2ed6d70ec..86f4531e7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertPtActivationType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_PtActivationType(const PtActivationType_t& in, denm_msgs::PtActivationType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_PtActivationType(const denm_msgs::PtActivationType& in, PtActivationType_t& out) { - memset(&out, 0, sizeof(PtActivationType_t)); + memset(&out, 0, sizeof(PtActivationType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h index c6a6a4682..4e866b52e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferenceDenms.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ReferenceDenms(const ReferenceDenms_t& in, denm_msgs::ReferenceDenms& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::ActionID el; - toRos_ActionID(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::ActionID array; + toRos_ActionID(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_ReferenceDenms(const denm_msgs::ReferenceDenms& in, ReferenceDenms_t& out) { + memset(&out, 0, sizeof(ReferenceDenms_t)); - for (int i = 0; i < in.array.size(); ++i) { - ActionID_t* el = (ActionID_t*) calloc(1, sizeof(ActionID_t)); - toStruct_ActionID(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + ActionID_t array; + toStruct_ActionID(in.array[i], array); + ActionID_t* array_ptr = new ActionID_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h index c8c41c574..75c5434b0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertReferencePosition.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,10 +27,10 @@ SOFTWARE. #pragma once #include -#include #include #include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -44,6 +43,7 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ReferencePosition(const ReferencePosition_t& in, denm_msgs::ReferencePosition& out) { + toRos_Latitude(in.latitude, out.latitude); toRos_Longitude(in.longitude, out.longitude); toRos_PosConfidenceEllipse(in.positionConfidenceEllipse, out.position_confidence_ellipse); @@ -51,6 +51,7 @@ void toRos_ReferencePosition(const ReferencePosition_t& in, denm_msgs::Reference } void toStruct_ReferencePosition(const denm_msgs::ReferencePosition& in, ReferencePosition_t& out) { + memset(&out, 0, sizeof(ReferencePosition_t)); toStruct_Latitude(in.latitude, out.latitude); @@ -59,4 +60,4 @@ void toStruct_ReferencePosition(const denm_msgs::ReferencePosition& in, Referenc toStruct_Altitude(in.altitude, out.altitude); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h index 16b284d85..07d698e4a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceDistance.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RelevanceDistance(const RelevanceDistance_t& in, denm_msgs::RelevanceDistance& out) { + out.value = in; } void toStruct_RelevanceDistance(const denm_msgs::RelevanceDistance& in, RelevanceDistance_t& out) { - memset(&out, 0, sizeof(RelevanceDistance_t)); + memset(&out, 0, sizeof(RelevanceDistance_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h index 685e4a0d3..5a0e2806c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRelevanceTrafficDirection.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RelevanceTrafficDirection(const RelevanceTrafficDirection_t& in, denm_msgs::RelevanceTrafficDirection& out) { + out.value = in; } void toStruct_RelevanceTrafficDirection(const denm_msgs::RelevanceTrafficDirection& in, RelevanceTrafficDirection_t& out) { - memset(&out, 0, sizeof(RelevanceTrafficDirection_t)); + memset(&out, 0, sizeof(RelevanceTrafficDirection_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h index fe47f419c..6cf6f6e73 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRequestResponseIndication.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RequestResponseIndication(const RequestResponseIndication_t& in, denm_msgs::RequestResponseIndication& out) { + out.value = in; } void toStruct_RequestResponseIndication(const denm_msgs::RequestResponseIndication& in, RequestResponseIndication_t& out) { - memset(&out, 0, sizeof(RequestResponseIndication_t)); + memset(&out, 0, sizeof(RequestResponseIndication_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h index 0198db72e..c0fbbca09 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRescueAndRecoveryWorkInProgressSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RescueAndRecoveryWorkInProgressSubCauseCode(const RescueAndRecoveryWorkInProgressSubCauseCode_t& in, denm_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RescueAndRecoveryWorkInProgressSubCauseCode(const denm_msgs::RescueAndRecoveryWorkInProgressSubCauseCode& in, RescueAndRecoveryWorkInProgressSubCauseCode_t& out) { - memset(&out, 0, sizeof(RescueAndRecoveryWorkInProgressSubCauseCode_t)); + memset(&out, 0, sizeof(RescueAndRecoveryWorkInProgressSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h index a9681f65f..53159e602 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRestrictedTypes.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include -#include +#include #include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RestrictedTypes(const RestrictedTypes_t& in, denm_msgs::RestrictedTypes& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::StationType el; - toRos_StationType(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::StationType array; + toRos_StationType(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_RestrictedTypes(const denm_msgs::RestrictedTypes& in, RestrictedTypes_t& out) { + memset(&out, 0, sizeof(RestrictedTypes_t)); - for (int i = 0; i < in.array.size(); ++i) { - StationType_t* el = (StationType_t*) calloc(1, sizeof(StationType_t)); - toStruct_StationType(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + StationType_t array; + toStruct_StationType(in.array[i], array); + StationType_t* array_ptr = new StationType_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h index 4d29d4dcd..b348ad988 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RoadType(const RoadType_t& in, denm_msgs::RoadType& out) { + out.value = in; } void toStruct_RoadType(const denm_msgs::RoadType& in, RoadType_t& out) { - memset(&out, 0, sizeof(RoadType_t)); + memset(&out, 0, sizeof(RoadType_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h index 5aa13769b..f182aaff0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadWorksContainerExtended.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,15 +27,15 @@ SOFTWARE. #pragma once #include -#include -#include -#include -#include #include -#include +#include #include #include +#include +#include +#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -49,83 +48,112 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RoadWorksContainerExtended(const RoadWorksContainerExtended_t& in, denm_msgs::RoadWorksContainerExtended& out) { + if (in.lightBarSirenInUse) { toRos_LightBarSirenInUse(*in.lightBarSirenInUse, out.light_bar_siren_in_use); out.light_bar_siren_in_use_is_present = true; } + if (in.closedLanes) { toRos_ClosedLanes(*in.closedLanes, out.closed_lanes); out.closed_lanes_is_present = true; } + if (in.restriction) { toRos_RestrictedTypes(*in.restriction, out.restriction); out.restriction_is_present = true; } + if (in.speedLimit) { toRos_SpeedLimit(*in.speedLimit, out.speed_limit); out.speed_limit_is_present = true; } + if (in.incidentIndication) { toRos_CauseCode(*in.incidentIndication, out.incident_indication); out.incident_indication_is_present = true; } + if (in.recommendedPath) { toRos_ItineraryPath(*in.recommendedPath, out.recommended_path); out.recommended_path_is_present = true; } + if (in.startingPointSpeedLimit) { toRos_DeltaReferencePosition(*in.startingPointSpeedLimit, out.starting_point_speed_limit); out.starting_point_speed_limit_is_present = true; } + if (in.trafficFlowRule) { toRos_TrafficRule(*in.trafficFlowRule, out.traffic_flow_rule); out.traffic_flow_rule_is_present = true; } + if (in.referenceDenms) { toRos_ReferenceDenms(*in.referenceDenms, out.reference_denms); out.reference_denms_is_present = true; } + } void toStruct_RoadWorksContainerExtended(const denm_msgs::RoadWorksContainerExtended& in, RoadWorksContainerExtended_t& out) { + memset(&out, 0, sizeof(RoadWorksContainerExtended_t)); if (in.light_bar_siren_in_use_is_present) { - out.lightBarSirenInUse = (LightBarSirenInUse_t*) calloc(1, sizeof(LightBarSirenInUse_t)); - toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, *out.lightBarSirenInUse); + LightBarSirenInUse_t light_bar_siren_in_use; + toStruct_LightBarSirenInUse(in.light_bar_siren_in_use, light_bar_siren_in_use); + out.lightBarSirenInUse = new LightBarSirenInUse_t(light_bar_siren_in_use); } + if (in.closed_lanes_is_present) { - out.closedLanes = (ClosedLanes_t*) calloc(1, sizeof(ClosedLanes_t)); - toStruct_ClosedLanes(in.closed_lanes, *out.closedLanes); + ClosedLanes_t closed_lanes; + toStruct_ClosedLanes(in.closed_lanes, closed_lanes); + out.closedLanes = new ClosedLanes_t(closed_lanes); } + if (in.restriction_is_present) { - out.restriction = (RestrictedTypes_t*) calloc(1, sizeof(RestrictedTypes_t)); - toStruct_RestrictedTypes(in.restriction, *out.restriction); + RestrictedTypes_t restriction; + toStruct_RestrictedTypes(in.restriction, restriction); + out.restriction = new RestrictedTypes_t(restriction); } + if (in.speed_limit_is_present) { - out.speedLimit = (SpeedLimit_t*) calloc(1, sizeof(SpeedLimit_t)); - toStruct_SpeedLimit(in.speed_limit, *out.speedLimit); + SpeedLimit_t speed_limit; + toStruct_SpeedLimit(in.speed_limit, speed_limit); + out.speedLimit = new SpeedLimit_t(speed_limit); } + if (in.incident_indication_is_present) { - out.incidentIndication = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); - toStruct_CauseCode(in.incident_indication, *out.incidentIndication); + CauseCode_t incident_indication; + toStruct_CauseCode(in.incident_indication, incident_indication); + out.incidentIndication = new CauseCode_t(incident_indication); } + if (in.recommended_path_is_present) { - out.recommendedPath = (ItineraryPath_t*) calloc(1, sizeof(ItineraryPath_t)); - toStruct_ItineraryPath(in.recommended_path, *out.recommendedPath); + ItineraryPath_t recommended_path; + toStruct_ItineraryPath(in.recommended_path, recommended_path); + out.recommendedPath = new ItineraryPath_t(recommended_path); } + if (in.starting_point_speed_limit_is_present) { - out.startingPointSpeedLimit = (DeltaReferencePosition_t*) calloc(1, sizeof(DeltaReferencePosition_t)); - toStruct_DeltaReferencePosition(in.starting_point_speed_limit, *out.startingPointSpeedLimit); + DeltaReferencePosition_t starting_point_speed_limit; + toStruct_DeltaReferencePosition(in.starting_point_speed_limit, starting_point_speed_limit); + out.startingPointSpeedLimit = new DeltaReferencePosition_t(starting_point_speed_limit); } + if (in.traffic_flow_rule_is_present) { - out.trafficFlowRule = (TrafficRule_t*) calloc(1, sizeof(TrafficRule_t)); - toStruct_TrafficRule(in.traffic_flow_rule, *out.trafficFlowRule); + TrafficRule_t traffic_flow_rule; + toStruct_TrafficRule(in.traffic_flow_rule, traffic_flow_rule); + out.trafficFlowRule = new TrafficRule_t(traffic_flow_rule); } + if (in.reference_denms_is_present) { - out.referenceDenms = (ReferenceDenms_t*) calloc(1, sizeof(ReferenceDenms_t)); - toStruct_ReferenceDenms(in.reference_denms, *out.referenceDenms); + ReferenceDenms_t reference_denms; + toStruct_ReferenceDenms(in.reference_denms, reference_denms); + out.referenceDenms = new ReferenceDenms_t(reference_denms); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h index abde4d483..fedfed25d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertRoadworksSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_RoadworksSubCauseCode(const RoadworksSubCauseCode_t& in, denm_msgs::RoadworksSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_RoadworksSubCauseCode(const denm_msgs::RoadworksSubCauseCode& in, RoadworksSubCauseCode_t& out) { - memset(&out, 0, sizeof(RoadworksSubCauseCode_t)); + memset(&out, 0, sizeof(RoadworksSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h index e0c0f53e3..32c58d57e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSemiAxisLength.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SemiAxisLength(const SemiAxisLength_t& in, denm_msgs::SemiAxisLength& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SemiAxisLength(const denm_msgs::SemiAxisLength& in, SemiAxisLength_t& out) { - memset(&out, 0, sizeof(SemiAxisLength_t)); + memset(&out, 0, sizeof(SemiAxisLength_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h index 4957b43f3..fca5a9ec7 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSequenceNumber.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SequenceNumber(const SequenceNumber_t& in, denm_msgs::SequenceNumber& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SequenceNumber(const denm_msgs::SequenceNumber& in, SequenceNumber_t& out) { - memset(&out, 0, sizeof(SequenceNumber_t)); + memset(&out, 0, sizeof(SequenceNumber_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h index 465b7ebcb..baed8b737 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSignalViolationSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SignalViolationSubCauseCode(const SignalViolationSubCauseCode_t& in, denm_msgs::SignalViolationSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SignalViolationSubCauseCode(const denm_msgs::SignalViolationSubCauseCode& in, SignalViolationSubCauseCode_t& out) { - memset(&out, 0, sizeof(SignalViolationSubCauseCode_t)); + memset(&out, 0, sizeof(SignalViolationSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h index f6f72682a..a205c9d61 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSituationContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,9 +27,10 @@ SOFTWARE. #pragma once #include +#include +#include #include #include -#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -43,31 +43,39 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SituationContainer(const SituationContainer_t& in, denm_msgs::SituationContainer& out) { + toRos_InformationQuality(in.informationQuality, out.information_quality); toRos_CauseCode(in.eventType, out.event_type); if (in.linkedCause) { toRos_CauseCode(*in.linkedCause, out.linked_cause); out.linked_cause_is_present = true; } + if (in.eventHistory) { toRos_EventHistory(*in.eventHistory, out.event_history); out.event_history_is_present = true; } + } void toStruct_SituationContainer(const denm_msgs::SituationContainer& in, SituationContainer_t& out) { + memset(&out, 0, sizeof(SituationContainer_t)); toStruct_InformationQuality(in.information_quality, out.informationQuality); toStruct_CauseCode(in.event_type, out.eventType); if (in.linked_cause_is_present) { - out.linkedCause = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); - toStruct_CauseCode(in.linked_cause, *out.linkedCause); + CauseCode_t linked_cause; + toStruct_CauseCode(in.linked_cause, linked_cause); + out.linkedCause = new CauseCode_t(linked_cause); } + if (in.event_history_is_present) { - out.eventHistory = (EventHistory_t*) calloc(1, sizeof(EventHistory_t)); - toStruct_EventHistory(in.event_history, *out.eventHistory); + EventHistory_t event_history; + toStruct_EventHistory(in.event_history, event_history); + out.eventHistory = new EventHistory_t(event_history); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h index afad97176..b91039d8d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSlowVehicleSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SlowVehicleSubCauseCode(const SlowVehicleSubCauseCode_t& in, denm_msgs::SlowVehicleSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SlowVehicleSubCauseCode(const denm_msgs::SlowVehicleSubCauseCode& in, SlowVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(SlowVehicleSubCauseCode_t)); + memset(&out, 0, sizeof(SlowVehicleSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h index 1bb17b9ac..aa8b49238 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpecialTransportType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,15 +41,16 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpecialTransportType(const SpecialTransportType_t& in, denm_msgs::SpecialTransportType& out) { + etsi_its_primitives_conversion::toRos_BIT_STRING(in, out.value); out.bits_unused = in.bits_unused; } void toStruct_SpecialTransportType(const denm_msgs::SpecialTransportType& in, SpecialTransportType_t& out) { - memset(&out, 0, sizeof(SpecialTransportType_t)); + memset(&out, 0, sizeof(SpecialTransportType_t)); etsi_its_primitives_conversion::toStruct_BIT_STRING(in.value, out); out.bits_unused = in.bits_unused; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h index 39c118f21..cc36d1058 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeed.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Speed(const Speed_t& in, denm_msgs::Speed& out) { + toRos_SpeedValue(in.speedValue, out.speed_value); toRos_SpeedConfidence(in.speedConfidence, out.speed_confidence); } void toStruct_Speed(const denm_msgs::Speed& in, Speed_t& out) { + memset(&out, 0, sizeof(Speed_t)); toStruct_SpeedValue(in.speed_value, out.speedValue); toStruct_SpeedConfidence(in.speed_confidence, out.speedConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h index 563eac70e..7f54bb247 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpeedConfidence(const SpeedConfidence_t& in, denm_msgs::SpeedConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedConfidence(const denm_msgs::SpeedConfidence& in, SpeedConfidence_t& out) { - memset(&out, 0, sizeof(SpeedConfidence_t)); + memset(&out, 0, sizeof(SpeedConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h index 17c6c335c..8d81fd8d6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedLimit.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpeedLimit(const SpeedLimit_t& in, denm_msgs::SpeedLimit& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedLimit(const denm_msgs::SpeedLimit& in, SpeedLimit_t& out) { - memset(&out, 0, sizeof(SpeedLimit_t)); + memset(&out, 0, sizeof(SpeedLimit_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h index 2ac727853..5763175be 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSpeedValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SpeedValue(const SpeedValue_t& in, denm_msgs::SpeedValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SpeedValue(const denm_msgs::SpeedValue& in, SpeedValue_t& out) { - memset(&out, 0, sizeof(SpeedValue_t)); + memset(&out, 0, sizeof(SpeedValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h index 18589bfbe..a9c582d93 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationID.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationID(const StationID_t& in, denm_msgs::StationID& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationID(const denm_msgs::StationID& in, StationID_t& out) { - memset(&out, 0, sizeof(StationID_t)); + memset(&out, 0, sizeof(StationID_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h index be4e973d1..eb342c4df 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationType(const StationType_t& in, denm_msgs::StationType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationType(const denm_msgs::StationType& in, StationType_t& out) { - memset(&out, 0, sizeof(StationType_t)); + memset(&out, 0, sizeof(StationType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h index 0e731a731..2ca20090a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationarySince.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationarySince(const StationarySince_t& in, denm_msgs::StationarySince& out) { + out.value = in; } void toStruct_StationarySince(const denm_msgs::StationarySince& in, StationarySince_t& out) { - memset(&out, 0, sizeof(StationarySince_t)); + memset(&out, 0, sizeof(StationarySince_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h index 9c8917e47..c20bcc9d6 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleContainer.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,12 +27,12 @@ SOFTWARE. #pragma once #include +#include #include #include -#include #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -46,59 +45,79 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationaryVehicleContainer(const StationaryVehicleContainer_t& in, denm_msgs::StationaryVehicleContainer& out) { + if (in.stationarySince) { toRos_StationarySince(*in.stationarySince, out.stationary_since); out.stationary_since_is_present = true; } + if (in.stationaryCause) { toRos_CauseCode(*in.stationaryCause, out.stationary_cause); out.stationary_cause_is_present = true; } + if (in.carryingDangerousGoods) { toRos_DangerousGoodsExtended(*in.carryingDangerousGoods, out.carrying_dangerous_goods); out.carrying_dangerous_goods_is_present = true; } + if (in.numberOfOccupants) { toRos_NumberOfOccupants(*in.numberOfOccupants, out.number_of_occupants); out.number_of_occupants_is_present = true; } + if (in.vehicleIdentification) { toRos_VehicleIdentification(*in.vehicleIdentification, out.vehicle_identification); out.vehicle_identification_is_present = true; } + if (in.energyStorageType) { toRos_EnergyStorageType(*in.energyStorageType, out.energy_storage_type); out.energy_storage_type_is_present = true; } + } void toStruct_StationaryVehicleContainer(const denm_msgs::StationaryVehicleContainer& in, StationaryVehicleContainer_t& out) { + memset(&out, 0, sizeof(StationaryVehicleContainer_t)); if (in.stationary_since_is_present) { - out.stationarySince = (StationarySince_t*) calloc(1, sizeof(StationarySince_t)); - toStruct_StationarySince(in.stationary_since, *out.stationarySince); + StationarySince_t stationary_since; + toStruct_StationarySince(in.stationary_since, stationary_since); + out.stationarySince = new StationarySince_t(stationary_since); } + if (in.stationary_cause_is_present) { - out.stationaryCause = (CauseCode_t*) calloc(1, sizeof(CauseCode_t)); - toStruct_CauseCode(in.stationary_cause, *out.stationaryCause); + CauseCode_t stationary_cause; + toStruct_CauseCode(in.stationary_cause, stationary_cause); + out.stationaryCause = new CauseCode_t(stationary_cause); } + if (in.carrying_dangerous_goods_is_present) { - out.carryingDangerousGoods = (DangerousGoodsExtended_t*) calloc(1, sizeof(DangerousGoodsExtended_t)); - toStruct_DangerousGoodsExtended(in.carrying_dangerous_goods, *out.carryingDangerousGoods); + DangerousGoodsExtended_t carrying_dangerous_goods; + toStruct_DangerousGoodsExtended(in.carrying_dangerous_goods, carrying_dangerous_goods); + out.carryingDangerousGoods = new DangerousGoodsExtended_t(carrying_dangerous_goods); } + if (in.number_of_occupants_is_present) { - out.numberOfOccupants = (NumberOfOccupants_t*) calloc(1, sizeof(NumberOfOccupants_t)); - toStruct_NumberOfOccupants(in.number_of_occupants, *out.numberOfOccupants); + NumberOfOccupants_t number_of_occupants; + toStruct_NumberOfOccupants(in.number_of_occupants, number_of_occupants); + out.numberOfOccupants = new NumberOfOccupants_t(number_of_occupants); } + if (in.vehicle_identification_is_present) { - out.vehicleIdentification = (VehicleIdentification_t*) calloc(1, sizeof(VehicleIdentification_t)); - toStruct_VehicleIdentification(in.vehicle_identification, *out.vehicleIdentification); + VehicleIdentification_t vehicle_identification; + toStruct_VehicleIdentification(in.vehicle_identification, vehicle_identification); + out.vehicleIdentification = new VehicleIdentification_t(vehicle_identification); } + if (in.energy_storage_type_is_present) { - out.energyStorageType = (EnergyStorageType_t*) calloc(1, sizeof(EnergyStorageType_t)); - toStruct_EnergyStorageType(in.energy_storage_type, *out.energyStorageType); + EnergyStorageType_t energy_storage_type; + toStruct_EnergyStorageType(in.energy_storage_type, energy_storage_type); + out.energyStorageType = new EnergyStorageType_t(energy_storage_type); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h index 354d6bfec..881ef8358 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertStationaryVehicleSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_StationaryVehicleSubCauseCode(const StationaryVehicleSubCauseCode_t& in, denm_msgs::StationaryVehicleSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_StationaryVehicleSubCauseCode(const denm_msgs::StationaryVehicleSubCauseCode& in, StationaryVehicleSubCauseCode_t& out) { - memset(&out, 0, sizeof(StationaryVehicleSubCauseCode_t)); + memset(&out, 0, sizeof(StationaryVehicleSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h index b26524c4a..375fc3525 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngle.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SteeringWheelAngle(const SteeringWheelAngle_t& in, denm_msgs::SteeringWheelAngle& out) { + toRos_SteeringWheelAngleValue(in.steeringWheelAngleValue, out.steering_wheel_angle_value); toRos_SteeringWheelAngleConfidence(in.steeringWheelAngleConfidence, out.steering_wheel_angle_confidence); } void toStruct_SteeringWheelAngle(const denm_msgs::SteeringWheelAngle& in, SteeringWheelAngle_t& out) { + memset(&out, 0, sizeof(SteeringWheelAngle_t)); toStruct_SteeringWheelAngleValue(in.steering_wheel_angle_value, out.steeringWheelAngleValue); toStruct_SteeringWheelAngleConfidence(in.steering_wheel_angle_confidence, out.steeringWheelAngleConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h index 0105189c1..75eb8ba84 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SteeringWheelAngleConfidence(const SteeringWheelAngleConfidence_t& in, denm_msgs::SteeringWheelAngleConfidence& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleConfidence(const denm_msgs::SteeringWheelAngleConfidence& in, SteeringWheelAngleConfidence_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleConfidence_t)); + memset(&out, 0, sizeof(SteeringWheelAngleConfidence_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h index b78458562..37fc7478f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSteeringWheelAngleValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SteeringWheelAngleValue(const SteeringWheelAngleValue_t& in, denm_msgs::SteeringWheelAngleValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SteeringWheelAngleValue(const denm_msgs::SteeringWheelAngleValue& in, SteeringWheelAngleValue_t& out) { - memset(&out, 0, sizeof(SteeringWheelAngleValue_t)); + memset(&out, 0, sizeof(SteeringWheelAngleValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h index 9375f23c5..e9966ae07 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertSubCauseCodeType.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_SubCauseCodeType(const SubCauseCodeType_t& in, denm_msgs::SubCauseCodeType& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_SubCauseCodeType(const denm_msgs::SubCauseCodeType& in, SubCauseCodeType_t& out) { - memset(&out, 0, sizeof(SubCauseCodeType_t)); + memset(&out, 0, sizeof(SubCauseCodeType_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h index 155709cdc..c6f404344 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTemperature.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Temperature(const Temperature_t& in, denm_msgs::Temperature& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_Temperature(const denm_msgs::Temperature& in, Temperature_t& out) { - memset(&out, 0, sizeof(Temperature_t)); + memset(&out, 0, sizeof(Temperature_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h index a83f40aef..dece171c0 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTermination.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Termination(const Termination_t& in, denm_msgs::Termination& out) { + out.value = in; } void toStruct_Termination(const denm_msgs::Termination& in, Termination_t& out) { - memset(&out, 0, sizeof(Termination_t)); + memset(&out, 0, sizeof(Termination_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h index 51d774356..5a65f5e99 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTimestampIts.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TimestampIts(const TimestampIts_t& in, denm_msgs::TimestampIts& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TimestampIts(const denm_msgs::TimestampIts& in, TimestampIts_t& out) { - memset(&out, 0, sizeof(TimestampIts_t)); + memset(&out, 0, sizeof(TimestampIts_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h index 3911ecb74..dfc4e9173 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTraces.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -29,13 +28,16 @@ SOFTWARE. #include +#include #include +#include #include -#include #ifdef ROS1 +#include #include namespace denm_msgs = etsi_its_denm_msgs; #else +#include #include namespace denm_msgs = etsi_its_denm_msgs::msg; #endif @@ -44,21 +46,27 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_Traces(const Traces_t& in, denm_msgs::Traces& out) { - for (int i = 0; i < in.list.count; ++i) { - denm_msgs::PathHistory el; - toRos_PathHistory(*(in.list.array[i]), el); - out.array.push_back(el); + + for (int i = 0; i < in.list.count; i++) { + denm_msgs::PathHistory array; + toRos_PathHistory(*(in.list.array[i]), array); + out.array.push_back(array); } + } void toStruct_Traces(const denm_msgs::Traces& in, Traces_t& out) { + memset(&out, 0, sizeof(Traces_t)); - for (int i = 0; i < in.array.size(); ++i) { - PathHistory_t* el = (PathHistory_t*) calloc(1, sizeof(PathHistory_t)); - toStruct_PathHistory(in.array[i], *el); - if (asn_sequence_add(&out, el)) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); + for (int i = 0; i < in.array.size(); i++) { + PathHistory_t array; + toStruct_PathHistory(in.array[i], array); + PathHistory_t* array_ptr = new PathHistory_t(array); + int status = asn_sequence_add(&out, array_ptr); + if (status != 0) throw std::invalid_argument("Failed to add to A_SEQUENCE_OF"); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h index d9710c2f8..59ebad3a5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficConditionSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TrafficConditionSubCauseCode(const TrafficConditionSubCauseCode_t& in, denm_msgs::TrafficConditionSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TrafficConditionSubCauseCode(const denm_msgs::TrafficConditionSubCauseCode& in, TrafficConditionSubCauseCode_t& out) { - memset(&out, 0, sizeof(TrafficConditionSubCauseCode_t)); + memset(&out, 0, sizeof(TrafficConditionSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h index 5020957db..e5b035043 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTrafficRule.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TrafficRule(const TrafficRule_t& in, denm_msgs::TrafficRule& out) { + out.value = in; } void toStruct_TrafficRule(const denm_msgs::TrafficRule& in, TrafficRule_t& out) { - memset(&out, 0, sizeof(TrafficRule_t)); + memset(&out, 0, sizeof(TrafficRule_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h index 5d8039e67..6af97b08a 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTransmissionInterval.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TransmissionInterval(const TransmissionInterval_t& in, denm_msgs::TransmissionInterval& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TransmissionInterval(const denm_msgs::TransmissionInterval& in, TransmissionInterval_t& out) { - memset(&out, 0, sizeof(TransmissionInterval_t)); + memset(&out, 0, sizeof(TransmissionInterval_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h index 947206be2..5a2095107 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertTurningRadius.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_TurningRadius(const TurningRadius_t& in, denm_msgs::TurningRadius& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_TurningRadius(const denm_msgs::TurningRadius& in, TurningRadius_t& out) { - memset(&out, 0, sizeof(TurningRadius_t)); + memset(&out, 0, sizeof(TurningRadius_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h index 56823c949..80c8cd0a2 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVDS.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VDS(const VDS_t& in, denm_msgs::VDS& out) { + etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_VDS(const denm_msgs::VDS& in, VDS_t& out) { - memset(&out, 0, sizeof(VDS_t)); + memset(&out, 0, sizeof(VDS_t)); etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h index 995348d95..3c0add6f5 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertValidityDuration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_ValidityDuration(const ValidityDuration_t& in, denm_msgs::ValidityDuration& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_ValidityDuration(const denm_msgs::ValidityDuration& in, ValidityDuration_t& out) { - memset(&out, 0, sizeof(ValidityDuration_t)); + memset(&out, 0, sizeof(ValidityDuration_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h index 6f8b7879e..d78e2f406 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleBreakdownSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleBreakdownSubCauseCode(const VehicleBreakdownSubCauseCode_t& in, denm_msgs::VehicleBreakdownSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleBreakdownSubCauseCode(const denm_msgs::VehicleBreakdownSubCauseCode& in, VehicleBreakdownSubCauseCode_t& out) { - memset(&out, 0, sizeof(VehicleBreakdownSubCauseCode_t)); + memset(&out, 0, sizeof(VehicleBreakdownSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h index 1928059bb..617bc4d1c 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleIdentification.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,27 +41,35 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleIdentification(const VehicleIdentification_t& in, denm_msgs::VehicleIdentification& out) { + if (in.wMInumber) { - toRos_WMInumber(*in.wMInumber, out.w_m_inumber); - out.w_m_inumber_is_present = true; + toRos_WMInumber(*in.wMInumber, out.wm_inumber); + out.wm_inumber_is_present = true; } + if (in.vDS) { - toRos_VDS(*in.vDS, out.v_ds); - out.v_ds_is_present = true; + toRos_VDS(*in.vDS, out.vds); + out.vds_is_present = true; } + } void toStruct_VehicleIdentification(const denm_msgs::VehicleIdentification& in, VehicleIdentification_t& out) { + memset(&out, 0, sizeof(VehicleIdentification_t)); - if (in.w_m_inumber_is_present) { - out.wMInumber = (WMInumber_t*) calloc(1, sizeof(WMInumber_t)); - toStruct_WMInumber(in.w_m_inumber, *out.wMInumber); + if (in.wm_inumber_is_present) { + WMInumber_t wm_inumber; + toStruct_WMInumber(in.wm_inumber, wm_inumber); + out.wMInumber = new WMInumber_t(wm_inumber); } - if (in.v_ds_is_present) { - out.vDS = (VDS_t*) calloc(1, sizeof(VDS_t)); - toStruct_VDS(in.v_ds, *out.vDS); + + if (in.vds_is_present) { + VDS_t vds; + toStruct_VDS(in.vds, vds); + out.vDS = new VDS_t(vds); } -} } + +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h index 93c5b423c..a22de9500 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLength.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleLength(const VehicleLength_t& in, denm_msgs::VehicleLength& out) { + toRos_VehicleLengthValue(in.vehicleLengthValue, out.vehicle_length_value); toRos_VehicleLengthConfidenceIndication(in.vehicleLengthConfidenceIndication, out.vehicle_length_confidence_indication); } void toStruct_VehicleLength(const denm_msgs::VehicleLength& in, VehicleLength_t& out) { + memset(&out, 0, sizeof(VehicleLength_t)); toStruct_VehicleLengthValue(in.vehicle_length_value, out.vehicleLengthValue); toStruct_VehicleLengthConfidenceIndication(in.vehicle_length_confidence_indication, out.vehicleLengthConfidenceIndication); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h index 140c73392..a489a6494 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthConfidenceIndication.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleLengthConfidenceIndication(const VehicleLengthConfidenceIndication_t& in, denm_msgs::VehicleLengthConfidenceIndication& out) { + out.value = in; } void toStruct_VehicleLengthConfidenceIndication(const denm_msgs::VehicleLengthConfidenceIndication& in, VehicleLengthConfidenceIndication_t& out) { - memset(&out, 0, sizeof(VehicleLengthConfidenceIndication_t)); + memset(&out, 0, sizeof(VehicleLengthConfidenceIndication_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h index 637387766..63d619b7b 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleLengthValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleLengthValue(const VehicleLengthValue_t& in, denm_msgs::VehicleLengthValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleLengthValue(const denm_msgs::VehicleLengthValue& in, VehicleLengthValue_t& out) { - memset(&out, 0, sizeof(VehicleLengthValue_t)); + memset(&out, 0, sizeof(VehicleLengthValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h index f83fcfefe..a4939b863 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleMass.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleMass(const VehicleMass_t& in, denm_msgs::VehicleMass& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleMass(const denm_msgs::VehicleMass& in, VehicleMass_t& out) { - memset(&out, 0, sizeof(VehicleMass_t)); + memset(&out, 0, sizeof(VehicleMass_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h index acf882da9..9fa69e3fe 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleRole.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleRole(const VehicleRole_t& in, denm_msgs::VehicleRole& out) { + out.value = in; } void toStruct_VehicleRole(const denm_msgs::VehicleRole& in, VehicleRole_t& out) { - memset(&out, 0, sizeof(VehicleRole_t)); + memset(&out, 0, sizeof(VehicleRole_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h index 4b6e92059..60605b632 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVehicleWidth.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VehicleWidth(const VehicleWidth_t& in, denm_msgs::VehicleWidth& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VehicleWidth(const denm_msgs::VehicleWidth& in, VehicleWidth_t& out) { - memset(&out, 0, sizeof(VehicleWidth_t)); + memset(&out, 0, sizeof(VehicleWidth_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h index 4b569cb76..e7ef2b099 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAcceleration.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VerticalAcceleration(const VerticalAcceleration_t& in, denm_msgs::VerticalAcceleration& out) { + toRos_VerticalAccelerationValue(in.verticalAccelerationValue, out.vertical_acceleration_value); toRos_AccelerationConfidence(in.verticalAccelerationConfidence, out.vertical_acceleration_confidence); } void toStruct_VerticalAcceleration(const denm_msgs::VerticalAcceleration& in, VerticalAcceleration_t& out) { + memset(&out, 0, sizeof(VerticalAcceleration_t)); toStruct_VerticalAccelerationValue(in.vertical_acceleration_value, out.verticalAccelerationValue); toStruct_AccelerationConfidence(in.vertical_acceleration_confidence, out.verticalAccelerationConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h index 482f4d24b..03614cceb 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertVerticalAccelerationValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_VerticalAccelerationValue(const VerticalAccelerationValue_t& in, denm_msgs::VerticalAccelerationValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_VerticalAccelerationValue(const denm_msgs::VerticalAccelerationValue& in, VerticalAccelerationValue_t& out) { - memset(&out, 0, sizeof(VerticalAccelerationValue_t)); + memset(&out, 0, sizeof(VerticalAccelerationValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h index e9d128c8b..3986ca61d 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWMInumber.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_WMInumber(const WMInumber_t& in, denm_msgs::WMInumber& out) { + etsi_its_primitives_conversion::toRos_IA5String(in, out.value); } void toStruct_WMInumber(const denm_msgs::WMInumber& in, WMInumber_t& out) { - memset(&out, 0, sizeof(WMInumber_t)); + memset(&out, 0, sizeof(WMInumber_t)); etsi_its_primitives_conversion::toStruct_IA5String(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h index 465af2cc9..4dd8c0735 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWheelBaseVehicle.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_WheelBaseVehicle(const WheelBaseVehicle_t& in, denm_msgs::WheelBaseVehicle& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WheelBaseVehicle(const denm_msgs::WheelBaseVehicle& in, WheelBaseVehicle_t& out) { - memset(&out, 0, sizeof(WheelBaseVehicle_t)); + memset(&out, 0, sizeof(WheelBaseVehicle_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h index 3db1f845c..fcdc94f8f 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertWrongWayDrivingSubCauseCode.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_WrongWayDrivingSubCauseCode(const WrongWayDrivingSubCauseCode_t& in, denm_msgs::WrongWayDrivingSubCauseCode& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_WrongWayDrivingSubCauseCode(const denm_msgs::WrongWayDrivingSubCauseCode& in, WrongWayDrivingSubCauseCode_t& out) { - memset(&out, 0, sizeof(WrongWayDrivingSubCauseCode_t)); + memset(&out, 0, sizeof(WrongWayDrivingSubCauseCode_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h index c040f7010..b84cf7f14 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRate.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,8 +27,8 @@ SOFTWARE. #pragma once #include -#include #include +#include #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -42,15 +41,17 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_YawRate(const YawRate_t& in, denm_msgs::YawRate& out) { + toRos_YawRateValue(in.yawRateValue, out.yaw_rate_value); toRos_YawRateConfidence(in.yawRateConfidence, out.yaw_rate_confidence); } void toStruct_YawRate(const denm_msgs::YawRate& in, YawRate_t& out) { + memset(&out, 0, sizeof(YawRate_t)); toStruct_YawRateValue(in.yaw_rate_value, out.yawRateValue); toStruct_YawRateConfidence(in.yaw_rate_confidence, out.yawRateConfidence); } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h index fd49f1d0b..7f5306470 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateConfidence.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -28,7 +27,6 @@ SOFTWARE. #pragma once #include - #ifdef ROS1 #include namespace denm_msgs = etsi_its_denm_msgs; @@ -41,13 +39,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_YawRateConfidence(const YawRateConfidence_t& in, denm_msgs::YawRateConfidence& out) { + out.value = in; } void toStruct_YawRateConfidence(const denm_msgs::YawRateConfidence& in, YawRateConfidence_t& out) { - memset(&out, 0, sizeof(YawRateConfidence_t)); + memset(&out, 0, sizeof(YawRateConfidence_t)); out = in.value; } -} +} \ No newline at end of file diff --git a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h index 292d48400..37493669e 100644 --- a/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h +++ b/etsi_its_conversion/etsi_its_denm_conversion/include/etsi_its_denm_conversion/convertYawRateValue.h @@ -2,7 +2,6 @@ MIT License Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal @@ -42,13 +41,14 @@ namespace denm_msgs = etsi_its_denm_msgs::msg; namespace etsi_its_denm_conversion { void toRos_YawRateValue(const YawRateValue_t& in, denm_msgs::YawRateValue& out) { + etsi_its_primitives_conversion::toRos_INTEGER(in, out.value); } void toStruct_YawRateValue(const denm_msgs::YawRateValue& in, YawRateValue_t& out) { - memset(&out, 0, sizeof(YawRateValue_t)); + memset(&out, 0, sizeof(YawRateValue_t)); etsi_its_primitives_conversion::toStruct_INTEGER(in.value, out); } -} +} \ No newline at end of file diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg index d8f12b08b..4a4e59cb3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 102 uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg index b9a2fcc83..e1729d637 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccelerationControl.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -47,3 +46,4 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg index 62efd6e30..b09fec1ee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AccidentSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg index 8ebd1d181..845afc0d2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ActionID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # sequenceNumber SequenceNumber # } # ------------------------------------------------------------------------------ + StationID originating_station_id SequenceNumber sequence_number diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 5e2955099..54039db9b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -43,3 +42,4 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 40958b76c..0e9e5babd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -39,3 +38,4 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index b087e8491..643edd4b2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 279aa3ad6..cecf863ab 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg index d33ad18f6..1e84f8bc4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Altitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # altitudeConfidence AltitudeConfidence # } # ------------------------------------------------------------------------------ + AltitudeValue altitude_value AltitudeConfidence altitude_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg index 0d49d5dfd..31c124195 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg index ced7117ff..404256f66 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/AltitudeValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 800001 int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg index 81d75ef19..b46724274 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # ... # } # ------------------------------------------------------------------------------ + StationType station_type ReferencePosition reference_position diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg index 93959b835..adfc414f6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -45,6 +44,7 @@ # cenDsrcTollingZone CenDsrcTollingZone OPTIONAL # } # ------------------------------------------------------------------------------ + Heading heading Speed speed diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg index a5cdf6b04..8de9fb81a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # pathHistory PathHistory # } # ------------------------------------------------------------------------------ + VehicleRole vehicle_role ExteriorLights exterior_lights diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg index c430f9ce8..ba24c19b0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CAM.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,7 +30,6 @@ # cam CoopAwareness # } # ------------------------------------------------------------------------------ -# The root data frame for cooperative awareness messages ItsPduHeader header diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg index 19f45ad71..99da1fd9f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CamParameters.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,6 +33,7 @@ # ... # } # ------------------------------------------------------------------------------ + BasicContainer basic_container HighFrequencyContainer high_frequency_container diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg index 9260033c6..13f0048db 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # ... # } # ------------------------------------------------------------------------------ + CauseCodeType cause_code SubCauseCodeType sub_cause_code diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg index c3034f85f..1a2cc7175 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CauseCodeType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -87,3 +86,4 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg index cf12d0483..39c0affef 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZone.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # ... # } # ------------------------------------------------------------------------------ + Latitude protected_zone_latitude Longitude protected_zone_longitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg index dd12f6a75..50b563c91 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,3 +29,4 @@ # ------------------------------------------------------------------------------ ProtectedZoneID value + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg index b4ff53fbf..4f4b22816 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ClosedLanes.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # ... # } # ------------------------------------------------------------------------------ + HardShoulderStatus innerhard_shoulder_status bool innerhard_shoulder_status_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg index 088c70f41..cbd4d715a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CollisionRiskSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg index ea7c612ee..78fc94758 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CoopAwareness.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # camParameters CamParameters # } # ------------------------------------------------------------------------------ + GenerationDeltaTime generation_delta_time CamParameters cam_parameters diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg index c9f50f1b2..ac99ea8a4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Curvature.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # curvatureConfidence CurvatureConfidence # } # ------------------------------------------------------------------------------ + CurvatureValue curvature_value CurvatureConfidence curvature_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg index c7166a4dd..65473f0cb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureCalculationMode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg index 014ac9603..56dea214e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg index ebb64831c..f3ce6a111 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/CurvatureValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ int16 MIN = -1023 int16 MAX = 1023 int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index 5625ad6c4..4461c2203 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg index f49e5e2bc..44ae47a36 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsBasic.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg index a2c6c2048..ef0650e50 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # dangerousGoodsBasic DangerousGoodsBasic # } # ------------------------------------------------------------------------------ + DangerousGoodsBasic dangerous_goods_basic diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg index 38e4e4c18..1b059d622 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousGoodsExtended.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,6 +37,7 @@ # ... # } # ------------------------------------------------------------------------------ + DangerousGoodsBasic dangerous_goods_type uint16 un_number diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg index ff8f082b4..742d6696b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DangerousSituationSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -40,3 +39,4 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg index 42e3c7d66..e8e7cd2c8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaAltitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 12800 int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg index 8316b7c49..b4d53fc21 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLatitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg index 001a1fa12..09e330c8d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaLongitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg index fd91f916d..687e6a5be 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DeltaReferencePosition.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # deltaAltitude DeltaAltitude # } # ------------------------------------------------------------------------------ + DeltaLatitude delta_latitude DeltaLongitude delta_longitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg index 9b9b8097a..d66dfc374 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DigitalMap.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ ReferencePosition[] array uint16 MIN_SIZE = 1 uint16 MAX_SIZE = 256 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg index 75d1f4936..4bb4caf19 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DriveDirection.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg index f55056461..682d819d3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/DrivingLaneStatus.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg index d0be1971f..80ae25981 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmbarkationStatus.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg index b75278ae1..c4b986317 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # emergencyPriority EmergencyPriority OPTIONAL # } # ------------------------------------------------------------------------------ + LightBarSirenInUse light_bar_siren_in_use CauseCode incident_indication diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg index fec313c25..0d7afaae7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyPriority.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 119607ee3..d88a0b461 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg index c8d184879..104cabb0c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EnergyStorageType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -39,3 +38,4 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg index 7171933f8..e31ae24c9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventHistory.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ EventPoint[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 23 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg index 4514b8d6b..c4f7df89c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/EventPoint.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # informationQuality InformationQuality # } # ------------------------------------------------------------------------------ + DeltaReferencePosition event_position PathDeltaTime event_delta_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg index bf1abac96..ce43d902b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ExteriorLights.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -49,3 +48,4 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg index afd9c27d9..e6345ff2f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/GenerationDeltaTime.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,3 +32,4 @@ uint16 value uint16 MIN = 0 uint16 MAX = 65535 uint16 ONE_MILLI_SEC = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg index b829dcda2..dcb4d381b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HardShoulderStatus.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 4766634a3..3bffb4cc1 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index 02551d9e1..ca7152557 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,3 +37,4 @@ uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index d0eee3f2e..4efb4942d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -40,3 +39,4 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 4e147ca9d..d26c8146b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -42,3 +41,4 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg index 79915064f..1b545cca4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Heading.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # headingConfidence HeadingConfidence # } # ------------------------------------------------------------------------------ + HeadingValue heading_value HeadingConfidence heading_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg index e449a7d2a..1ee4827f9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg index 01ecf4177..e670dc588 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeadingValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint16 WGS_84_EAST = 900 uint16 WGS_84_SOUTH = 1800 uint16 WGS_84_WEST = 2700 uint16 UNAVAILABLE = 3601 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg index a57e51b95..e496a3825 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HeightLonCarr.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 100 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg index fe78d1406..d986e3bb6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HighFrequencyContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # ... # } # ------------------------------------------------------------------------------ + uint8 choice BasicVehicleContainerHighFrequency basic_vehicle_container_high_frequency diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index a59935c0a..b3d865712 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg index 50d2c72b9..bde36b417 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/HumanProblemSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg index aaa05b44b..cf40d52ab 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/InformationQuality.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg index cba1ae5eb..c1adc8ce9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItineraryPath.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ ReferencePosition[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 40 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg index f7a6a34b0..9957d5f0e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ItsPduHeader.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,6 +29,7 @@ # protocolVersion INTEGER (0..255), # messageID INTEGER{ denm(1), cam(2), poi(3), spatem(4), mapem(5), ivim(6), ev-rsr(7), tistpgtransaction(8), srem(9), ssem(10), evcsn(11), saem(12), rtcmem(13) } (0..255), -- Mantis #7209, #7005 # ------------------------------------------------------------------------------ + uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 uint8 PROTOCOL_VERSION_MAX = 255 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg index cf2c4184e..8ee066832 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LanePosition.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg index 3e2f5d914..9ac6f4836 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAcceleration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # lateralAccelerationConfidence AccelerationConfidence # } # ------------------------------------------------------------------------------ + LateralAccelerationValue lateral_acceleration_value AccelerationConfidence lateral_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg index c0c95cdf3..f9b4f8b73 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LateralAccelerationValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg index d6790b6a7..2dc42bbcb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Latitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 900000001 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg index af41f3d23..a9bbe9282 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LightBarSirenInUse.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg index 0d881d795..8678c6e5a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Longitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 1800000001 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg index f8ce9be22..2950f6914 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAcceleration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # longitudinalAccelerationConfidence AccelerationConfidence # } # ------------------------------------------------------------------------------ + LongitudinalAccelerationValue longitudinal_acceleration_value AccelerationConfidence longitudinal_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg index 5490b1049..ae8f739f8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg index 26667688c..5ddc6a8a3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/LowFrequencyContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # ... # } # ------------------------------------------------------------------------------ + uint8 choice BasicVehicleContainerLowFrequency basic_vehicle_container_low_frequency diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg index 29866b9b5..4cc239cad 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/NumberOfOccupants.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 0 uint8 MAX = 127 uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg index 3ca9fd400..bc47f7c8b 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/OpeningDaysHours.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg index eb535a512..04ad62a14 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathDeltaTime.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -29,7 +28,8 @@ # PathDeltaTime ::= INTEGER {tenMilliSecondsInPast(1)} (1..65535, ...) # ------------------------------------------------------------------------------ -int64 value -int64 MIN = 1 -int64 MAX = 65535 -int64 TEN_MILLI_SECONDS_IN_PAST = 1 +uint16 value +uint16 MIN = 1 +uint16 MAX = 65535 +uint16 TEN_MILLI_SECONDS_IN_PAST = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg index a01230954..f45476300 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathHistory.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ PathPoint[] array uint8 MIN_SIZE = 0 uint8 MAX_SIZE = 40 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg index beb29a984..afe56fd92 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PathPoint.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # pathDeltaTime PathDeltaTime OPTIONAL # } # ------------------------------------------------------------------------------ + DeltaReferencePosition path_position PathDeltaTime path_delta_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg index 5e647048f..566e6c9ae 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PerformanceClass.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg index c905f4171..6efe47e5d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PhoneNumber.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ string value uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 16 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg index eb542bcf9..18fdd9a5c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosCentMass.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 63 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg index 69e6be2a2..0c72b9a6f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosConfidenceEllipse.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # semiMajorOrientation HeadingValue # } # ------------------------------------------------------------------------------ + SemiAxisLength semi_major_confidence SemiAxisLength semi_minor_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg index dec614584..622ab1d0f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosFrontAx.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 20 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg index 56a23793c..5d6168e9f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosLonCarr.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg index f000268e6..050b310d7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PosPillar.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 30 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg index bab7e4e92..f11996d64 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfOccupants.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -72,3 +71,4 @@ uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg index 7db286c34..eea208f31 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositionOfPillars.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # ------------------------------------------------------------------------------ PosPillar[] array -int64 MIN_SIZE = 1 -int64 MAX_SIZE = 3 +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg index 1032ae4b1..e0292c4ea 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PositioningSolutionType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,7 +32,7 @@ uint8 value uint8 NO_POSITIONING_SOLUTION = 0 uint8 S_GNSS = 1 uint8 D_GNSS = 2 -uint8 S_GNS_SPLUS_DR = 3 -uint8 D_GNS_SPLUS_DR = 4 +uint8 S_GNSS_PLUS_D_R = 3 +uint8 D_GNSS_PLUS_D_R = 4 uint8 D_R = 5 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg index 85a35798a..bee1a897e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PostCrashSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg index d1335c7cc..5a6ebbbd4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,6 +35,7 @@ # ... # } # ------------------------------------------------------------------------------ + ProtectedZoneType protected_zone_type TimestampIts expiry_time diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg index 2d5f9f9a4..cc6d8ea62 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ ProtectedCommunicationZone[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 16 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg index bb4f93c32..6a0344d74 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg index 97a3ead2e..7f1a3f2c2 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneRadius.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -29,7 +28,8 @@ # ProtectedZoneRadius ::= INTEGER {oneMeter(1)} (1..255,...) # ------------------------------------------------------------------------------ -int64 value -int64 MIN = 1 -int64 MAX = 255 -int64 ONE_METER = 1 +uint8 value +uint8 MIN = 1 +uint8 MAX = 255 +uint8 ONE_METER = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg index 9ba419cec..3283db4e0 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ProtectedZoneType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,5 @@ uint8 value uint8 PERMANENT_CEN_DSRC_TOLLING = 0 -# .extended uint8 TEMPORARY_CEN_DSRC_TOLLING = 1 diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg index 32c276aa5..f70514140 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivation.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # ptActivationData PtActivationData # } # ------------------------------------------------------------------------------ + PtActivationType pt_activation_type PtActivationData pt_activation_data diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg index 902dbf9e0..0fb3a6413 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationData.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ uint8[] value uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 20 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg index 1d3a14412..0d373552c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PtActivationType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNDEFINED_CODING_TYPE = 0 uint8 R_09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg index 109418c87..c6f767b3c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/PublicTransportContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # ptActivation PtActivation OPTIONAL # } # ------------------------------------------------------------------------------ + EmbarkationStatus embarkation_status PtActivation pt_activation diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg index 61c0ce7ec..c75e9fee3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # ... # } # ------------------------------------------------------------------------------ + ProtectedCommunicationZonesRSU protected_communication_zones_rsu bool protected_communication_zones_rsu_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg index 738b78443..ff37f4ebf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ReferencePosition.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # altitude Altitude # } # ------------------------------------------------------------------------------ + Latitude latitude Longitude longitude diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg index 4bdc9a00c..03f962736 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceDistance.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg index 23849c372..6a2060b60 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RelevanceTrafficDirection.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg index 7a88dc8db..e87b70032 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RequestResponseIndication.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index 427e20f40..3cd20fa4f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,3 +37,4 @@ uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg index e4be99071..197d53528 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RescueContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # lightBarSirenInUse LightBarSirenInUse # } # ------------------------------------------------------------------------------ + LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg index f9c80d5be..d5103c64e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RestrictedTypes.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # ------------------------------------------------------------------------------ StationType[] array -int64 MIN_SIZE = 1 -int64 MAX_SIZE = 3 +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg index 7280b7c6b..e2615acec 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg index 3525a2c3e..cc3058338 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # closedLanes ClosedLanes OPTIONAL # } # ------------------------------------------------------------------------------ + RoadworksSubCauseCode roadworks_sub_cause_code bool roadworks_sub_cause_code_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg index 017a34d21..153e11c4e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -39,3 +38,4 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg index 3ac82382a..cc44061fb 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SafetyCarContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # speedLimit SpeedLimit OPTIONAL # } # ------------------------------------------------------------------------------ + LightBarSirenInUse light_bar_siren_in_use CauseCode incident_indication diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg index fbd569ec1..976c006d8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SemiAxisLength.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint16 MAX = 4095 uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg index 8fd8be07e..3ee9128cd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SequenceNumber.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg index 6286201a3..580af19c9 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SignalViolationSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg index ffc371dec..d7c7e96b7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SlowVehicleSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg index e1c057461..15becf54c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # lightBarSirenInUse LightBarSirenInUse # } # ------------------------------------------------------------------------------ + SpecialTransportType special_transport_type LightBarSirenInUse light_bar_siren_in_use diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg index 7bfb3f184..8f5fcd9d6 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialTransportType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg index 3ca723811..2235487fe 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpecialVehicleContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,6 +36,7 @@ # ... # } # ------------------------------------------------------------------------------ + uint8 choice PublicTransportContainer public_transport_container diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg index e6a686f59..ecfc591e4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Speed.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # speedConfidence SpeedConfidence # } # ------------------------------------------------------------------------------ + SpeedValue speed_value SpeedConfidence speed_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg index 3001fa3f3..487873b36 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg index 5eb6c64c4..4cf1a9d03 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedLimit.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,3 +32,4 @@ uint8 value uint8 MIN = 1 uint8 MAX = 255 uint8 ONE_KM_PER_HOUR = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg index 978abe6e5..b3d89beff 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SpeedValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint16 MAX = 16383 uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg index 6cf2e47dc..9d36a5a65 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg index d84cf4192..104c6821e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -46,3 +45,4 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg index 6cd027626..e0133c7a8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationarySince.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg index a970bdcb5..190a7c78e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,3 +37,4 @@ uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg index eb08c754b..918cc7a8d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngle.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # steeringWheelAngleConfidence SteeringWheelAngleConfidence # } # ------------------------------------------------------------------------------ + SteeringWheelAngleValue steering_wheel_angle_value SteeringWheelAngleConfidence steering_wheel_angle_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg index 9c07b52b0..bf209a62e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 127 uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg index aeae3ce54..fbda5ff63 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg index ebc0b6600..5f328fa69 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/SubCauseCodeType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg index 0a3e27072..2e351568e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Temperature.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int8 MAX = 67 int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 int8 ONE_DEGREE_CELSIUS = 1 int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg index 8366db355..6871563ba 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TimestampIts.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint64 MIN = 0 uint64 MAX = 4398046511103 uint64 UTC_START_OF_2004 = 0 uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg index f3a2e2a48..db7a2bb0f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/Traces.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ PathHistory[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 7 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg index 41b2503eb..38061b4a4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficConditionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg index c688d0470..cc8afc852 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TrafficRule.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg index e2f87591d..343d094dd 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TransmissionInterval.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint16 MIN = 1 uint16 MAX = 10000 uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg index 510f64696..99ccaa91d 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/TurningRadius.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 255 uint8 POINT_4_METERS = 1 uint8 UNAVAILABLE = 255 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg index 80ffff83c..e9beb0f3f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VDS.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,3 +30,4 @@ string value uint8 SIZE = 6 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg index 9e069e511..3cfc6ffe7 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/ValidityDuration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint32 MIN = 0 uint32 MAX = 86400 uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg index 814d2276a..40c794fa4 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -42,3 +41,4 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg index e43ea5841..411ade20f 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleIdentification.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,9 +31,10 @@ # ... # } # ------------------------------------------------------------------------------ -WMInumber w_m_inumber -bool w_m_inumber_is_present -VDS v_ds -bool v_ds_is_present +WMInumber wm_inumber +bool wm_inumber_is_present + +VDS vds +bool vds_is_present diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg index 0b68fb8ef..0657adbdc 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLength.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # vehicleLengthConfidenceIndication VehicleLengthConfidenceIndication # } # ------------------------------------------------------------------------------ + VehicleLengthValue vehicle_length_value VehicleLengthConfidenceIndication vehicle_length_confidence_indication diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg index 5b5d5d4c7..b5a008bba 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg index baed0b1ee..e253cfda3 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleLengthValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint16 MAX = 1023 uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg index 986aab8fc..d74f09b5c 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleMass.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint16 MIN = 1 uint16 MAX = 1024 uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg index 3e089a89a..daeb43921 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleRole.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg index b0a8e7fa5..c209c3b57 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VehicleWidth.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 62 uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg index 0ac4bda1a..3da431c59 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAcceleration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # verticalAccelerationConfidence AccelerationConfidence # } # ------------------------------------------------------------------------------ + VerticalAccelerationValue vertical_acceleration_value AccelerationConfidence vertical_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg index f0abb220c..4f208993e 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/VerticalAccelerationValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg index 22d1ceeab..34b682f9a 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WMInumber.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ string value uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 3 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg index 0b7a691a5..af24dccaf 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WheelBaseVehicle.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg index a4611cb8c..0f8080f05 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 + diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg index 7305b6027..2284e9ba8 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRate.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # yawRateConfidence YawRateConfidence # } # ------------------------------------------------------------------------------ + YawRateValue yaw_rate_value YawRateConfidence yaw_rate_confidence diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg index a3a9eaab3..4150e4776 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg index 3cf3b6b18..9564c6bee 100644 --- a/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_cam_msgs/msg/YawRateValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg index d8f12b08b..4a4e59cb3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 102 uint8 POINT_ONE_METER_PER_SEC_SQUARED = 1 uint8 OUT_OF_RANGE = 101 uint8 UNAVAILABLE = 102 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg index b9a2fcc83..e1729d637 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccelerationControl.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -47,3 +46,4 @@ uint8 BIT_INDEX_COLLISION_WARNING_ENGAGED = 3 uint8 BIT_INDEX_ACC_ENGAGED = 4 uint8 BIT_INDEX_CRUISE_CONTROL_ENGAGED = 5 uint8 BIT_INDEX_SPEED_LIMITER_ENGAGED = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg index 62efd6e30..b09fec1ee 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AccidentSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 ACCIDENT_INVOLVING_HAZARDOUS_MATERIALS = 5 uint8 ACCIDENT_ON_OPPOSITE_LANE = 6 uint8 UNSECURED_ACCIDENT = 7 uint8 ASSISTANCE_REQUESTED = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg index 8ebd1d181..845afc0d2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ActionID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # sequenceNumber SequenceNumber # } # ------------------------------------------------------------------------------ + StationID originating_station_id SequenceNumber sequence_number diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg index 5e2955099..54039db9b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionAdhesionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -43,3 +42,4 @@ uint8 OIL_ON_ROAD = 7 uint8 LOOSE_CHIPPINGS = 8 uint8 INSTANT_BLACK_ICE = 9 uint8 ROADS_SALTED = 10 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg index 40958b76c..0e9e5babd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionExtremeWeatherConditionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -39,3 +38,4 @@ uint8 HURRICANE = 3 uint8 THUNDERSTORM = 4 uint8 TORNADO = 5 uint8 BLIZZARD = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg index b087e8491..643edd4b2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionPrecipitationSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 UNAVAILABLE = 0 uint8 HEAVY_RAIN = 1 uint8 HEAVY_SNOWFALL = 2 uint8 SOFT_HAIL = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg index 279aa3ad6..cecf863ab 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AdverseWeatherConditionVisibilitySubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 HEAVY_HAIL = 5 uint8 LOW_SUN_GLARE = 6 uint8 SANDSTORMS = 7 uint8 SWARMS_OF_INSECTS = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg index f9f8d8bfb..72f86507e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AlacarteContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,6 +35,7 @@ # ... # } # ------------------------------------------------------------------------------ + LanePosition lane_position bool lane_position_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg index d33ad18f6..1e84f8bc4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Altitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # altitudeConfidence AltitudeConfidence # } # ------------------------------------------------------------------------------ + AltitudeValue altitude_value AltitudeConfidence altitude_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg index 0d49d5dfd..31c124195 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg index ced7117ff..404256f66 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/AltitudeValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 800001 int32 REFERENCE_ELLIPSOID_SURFACE = 0 int32 ONE_CENTIMETER = 1 int32 UNAVAILABLE = 800001 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg index 9260033c6..13f0048db 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # ... # } # ------------------------------------------------------------------------------ + CauseCodeType cause_code SubCauseCodeType sub_cause_code diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg index c3034f85f..1a2cc7175 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CauseCodeType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -87,3 +86,4 @@ uint8 HAZARDOUS_LOCATION_DANGEROUS_CURVE = 96 uint8 COLLISION_RISK = 97 uint8 SIGNAL_VIOLATION = 98 uint8 DANGEROUS_SITUATION = 99 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg index cf12d0483..39c0affef 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZone.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # ... # } # ------------------------------------------------------------------------------ + Latitude protected_zone_latitude Longitude protected_zone_longitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg index dd12f6a75..50b563c91 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CenDsrcTollingZoneID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,3 +29,4 @@ # ------------------------------------------------------------------------------ ProtectedZoneID value + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg index b4ff53fbf..4f4b22816 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ClosedLanes.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # ... # } # ------------------------------------------------------------------------------ + HardShoulderStatus innerhard_shoulder_status bool innerhard_shoulder_status_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg index 088c70f41..cbd4d715a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CollisionRiskSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 LONGITUDINAL_COLLISION_RISK = 1 uint8 CROSSING_COLLISION_RISK = 2 uint8 LATERAL_COLLISION_RISK = 3 uint8 VULNERABLE_ROAD_USER = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg index c9f50f1b2..ac99ea8a4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Curvature.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # curvatureConfidence CurvatureConfidence # } # ------------------------------------------------------------------------------ + CurvatureValue curvature_value CurvatureConfidence curvature_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg index c7166a4dd..65473f0cb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureCalculationMode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg index 014ac9603..56dea214e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg index ebb64831c..f3ce6a111 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/CurvatureValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ int16 MIN = -1023 int16 MAX = 1023 int16 STRAIGHT = 0 int16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg index 78254d73e..4b35bddb9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DENM.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # denm DecentralizedEnvironmentalNotificationMessage # } # ------------------------------------------------------------------------------ + ItsPduHeader header DecentralizedEnvironmentalNotificationMessage denm diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg index 5625ad6c4..4461c2203 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousEndOfQueueSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 SUDDEN_END_OF_QUEUE = 1 uint8 QUEUE_OVER_HILL = 2 uint8 QUEUE_AROUND_BEND = 3 uint8 QUEUE_IN_TUNNEL = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg index f49e5e2bc..44ae47a36 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsBasic.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg index 38e4e4c18..1b059d622 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousGoodsExtended.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,6 +37,7 @@ # ... # } # ------------------------------------------------------------------------------ + DangerousGoodsBasic dangerous_goods_type uint16 un_number diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg index ff8f082b4..742d6696b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DangerousSituationSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -40,3 +39,4 @@ uint8 ABS_ENGAGED = 4 uint8 AEB_ENGAGED = 5 uint8 BRAKE_WARNING_ENGAGED = 6 uint8 COLLISION_RISK_WARNING_ENGAGED = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg index 0095eceeb..c35062a0a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DecentralizedEnvironmentalNotificationMessage.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # alacarte AlacarteContainer OPTIONAL # } # ------------------------------------------------------------------------------ + ManagementContainer management SituationContainer situation diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg index 42e3c7d66..e8e7cd2c8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaAltitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 12800 int16 ONE_CENTIMETER_UP = 1 int16 ONE_CENTIMETER_DOWN = -1 int16 UNAVAILABLE = 12800 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg index 8316b7c49..b4d53fc21 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLatitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg index 001a1fa12..09e330c8d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaLongitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 131072 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 131072 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg index fd91f916d..687e6a5be 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DeltaReferencePosition.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # deltaAltitude DeltaAltitude # } # ------------------------------------------------------------------------------ + DeltaLatitude delta_latitude DeltaLongitude delta_longitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg index 9b9b8097a..d66dfc374 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DigitalMap.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ ReferencePosition[] array uint16 MIN_SIZE = 1 uint16 MAX_SIZE = 256 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg index 75d1f4936..4bb4caf19 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DriveDirection.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg index f55056461..682d819d3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/DrivingLaneStatus.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg index d0be1971f..80ae25981 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmbarkationStatus.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg index fec313c25..0d7afaae7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyPriority.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_REQUEST_FOR_RIGHT_OF_WAY = 0 uint8 BIT_INDEX_REQUEST_FOR_FREE_CROSSING_AT_A_TRAFFIC_LIGHT = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg index 119607ee3..d88a0b461 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EmergencyVehicleApproachingSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 EMERGENCY_VEHICLE_APPROACHING = 1 uint8 PRIORITIZED_VEHICLE_APPROACHING = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg index c8d184879..104cabb0c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EnergyStorageType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -39,3 +38,4 @@ uint8 BIT_INDEX_COMPRESSED_NATURAL_GAS = 3 uint8 BIT_INDEX_DIESEL = 4 uint8 BIT_INDEX_GASOLINE = 5 uint8 BIT_INDEX_AMMONIA = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg index 7171933f8..e31ae24c9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventHistory.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ EventPoint[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 23 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg index 4514b8d6b..c4f7df89c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/EventPoint.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # informationQuality InformationQuality # } # ------------------------------------------------------------------------------ + DeltaReferencePosition event_position PathDeltaTime event_delta_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg index bf1abac96..ce43d902b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ExteriorLights.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -49,3 +48,4 @@ uint8 BIT_INDEX_DAYTIME_RUNNING_LIGHTS_ON = 4 uint8 BIT_INDEX_REVERSE_LIGHT_ON = 5 uint8 BIT_INDEX_FOG_LIGHT_ON = 6 uint8 BIT_INDEX_PARKING_LIGHTS_ON = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg index b829dcda2..dcb4d381b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HardShoulderStatus.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg index 4766634a3..3bffb4cc1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationAnimalOnTheRoadSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 WILD_ANIMALS = 1 uint8 HERD_OF_ANIMALS = 2 uint8 SMALL_ANIMALS = 3 uint8 LARGE_ANIMALS = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg index 02551d9e1..ca7152557 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationDangerousCurveSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,3 +37,4 @@ uint8 DANGEROUS_RIGHT_TURN_CURVE = 2 uint8 MULTIPLE_CURVES_STARTING_WITH_UNKNOWN_TURNING_DIRECTION = 3 uint8 MULTIPLE_CURVES_STARTING_WITH_LEFT_TURN = 4 uint8 MULTIPLE_CURVES_STARTING_WITH_RIGHT_TURN = 5 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg index d0eee3f2e..4efb4942d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationObstacleOnTheRoadSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -40,3 +39,4 @@ uint8 BIG_OBJECTS = 4 uint8 FALLEN_TREES = 5 uint8 HUB_CAPS = 6 uint8 WAITING_VEHICLES = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg index 4e147ca9d..d26c8146b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HazardousLocationSurfaceConditionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -42,3 +41,4 @@ uint8 STORM_DAMAGE = 6 uint8 BURST_PIPE = 7 uint8 VOLCANO_ERUPTION = 8 uint8 FALLING_ICE = 9 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg index 79915064f..1b545cca4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Heading.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # headingConfidence HeadingConfidence # } # ------------------------------------------------------------------------------ + HeadingValue heading_value HeadingConfidence heading_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg index e449a7d2a..1ee4827f9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 EQUAL_OR_WITHIN_ZERO_POINT_ONE_DEGREE = 1 uint8 EQUAL_OR_WITHIN_ONE_DEGREE = 10 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg index 01ecf4177..e670dc588 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeadingValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint16 WGS_84_EAST = 900 uint16 WGS_84_SOUTH = 1800 uint16 WGS_84_WEST = 2700 uint16 UNAVAILABLE = 3601 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg index a57e51b95..e496a3825 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HeightLonCarr.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 100 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 100 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg index a59935c0a..b3d865712 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanPresenceOnTheRoadSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 UNAVAILABLE = 0 uint8 CHILDREN_ON_ROADWAY = 1 uint8 CYCLIST_ON_ROADWAY = 2 uint8 MOTORCYCLIST_ON_ROADWAY = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg index 50d2c72b9..bde36b417 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/HumanProblemSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 GLYCEMIA_PROBLEM = 1 uint8 HEART_PROBLEM = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg index bc60e4ae8..99e840cb4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ImpactReductionContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,6 +40,7 @@ # requestResponseIndication RequestResponseIndication # } # ------------------------------------------------------------------------------ + HeightLonCarr height_lon_carr_left HeightLonCarr height_lon_carr_right diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg index aaa05b44b..cf40d52ab 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/InformationQuality.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 LOWEST = 1 uint8 HIGHEST = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg index cba1ae5eb..c1adc8ce9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItineraryPath.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ ReferencePosition[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 40 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg index f7a6a34b0..9957d5f0e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ItsPduHeader.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,6 +29,7 @@ # protocolVersion INTEGER (0..255), # messageID INTEGER{ denm(1), cam(2), poi(3), spatem(4), mapem(5), ivim(6), ev-rsr(7), tistpgtransaction(8), srem(9), ssem(10), evcsn(11), saem(12), rtcmem(13) } (0..255), -- Mantis #7209, #7005 # ------------------------------------------------------------------------------ + uint8 protocol_version uint8 PROTOCOL_VERSION_MIN = 0 uint8 PROTOCOL_VERSION_MAX = 255 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg index cf2c4184e..8ee066832 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LanePosition.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ int8 OFF_THE_ROAD = -1 int8 HARD_SHOULDER = 0 int8 OUTERMOST_DRIVING_LANE = 1 int8 SECOND_LANE_FROM_OUTSIDE = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg index 3e2f5d914..9ac6f4836 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAcceleration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # lateralAccelerationConfidence AccelerationConfidence # } # ------------------------------------------------------------------------------ + LateralAccelerationValue lateral_acceleration_value AccelerationConfidence lateral_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg index c0c95cdf3..f9b4f8b73 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LateralAccelerationValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_RIGHT = -1 int16 POINT_ONE_METER_PER_SEC_SQUARED_TO_LEFT = 1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg index d6790b6a7..2dc42bbcb 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Latitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 900000001 int32 ONE_MICRODEGREE_NORTH = 10 int32 ONE_MICRODEGREE_SOUTH = -10 int32 UNAVAILABLE = 900000001 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg index af41f3d23..a9bbe9282 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LightBarSirenInUse.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 bits_unused uint8 SIZE_BITS = 2 uint8 BIT_INDEX_LIGHT_BAR_ACTIVATED = 0 uint8 BIT_INDEX_SIREN_ACTIVATED = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg index 0f3715012..85ebfdb29 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LocationContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,6 +33,7 @@ # ... # } # ------------------------------------------------------------------------------ + Speed event_speed bool event_speed_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg index 0d881d795..8678c6e5a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Longitude.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int32 MAX = 1800000001 int32 ONE_MICRODEGREE_EAST = 10 int32 ONE_MICRODEGREE_WEST = -10 int32 UNAVAILABLE = 1800000001 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg index f8ce9be22..2950f6914 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAcceleration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # longitudinalAccelerationConfidence AccelerationConfidence # } # ------------------------------------------------------------------------------ + LongitudinalAccelerationValue longitudinal_acceleration_value AccelerationConfidence longitudinal_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg index 5490b1049..ae8f739f8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/LongitudinalAccelerationValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_FORWARD = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_BACKWARD = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg index 618922061..e764409b4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ManagementContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -40,6 +39,7 @@ # ... # } # ------------------------------------------------------------------------------ + ActionID action_id TimestampIts detection_time @@ -58,11 +58,10 @@ RelevanceTrafficDirection relevance_traffic_direction bool relevance_traffic_direction_is_present ValidityDuration validity_duration +uint16 DEFAULT_VALIDITY_DURATION = 600 TransmissionInterval transmission_interval bool transmission_interval_is_present StationType station_type - -uint32 VALIDITY_DURATION_DEFAULT = 600 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg index 29866b9b5..4cc239cad 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/NumberOfOccupants.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 0 uint8 MAX = 127 uint8 ONE_OCCUPANT = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg index 3ca9fd400..bc47f7c8b 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/OpeningDaysHours.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg index eb535a512..04ad62a14 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathDeltaTime.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -29,7 +28,8 @@ # PathDeltaTime ::= INTEGER {tenMilliSecondsInPast(1)} (1..65535, ...) # ------------------------------------------------------------------------------ -int64 value -int64 MIN = 1 -int64 MAX = 65535 -int64 TEN_MILLI_SECONDS_IN_PAST = 1 +uint16 value +uint16 MIN = 1 +uint16 MAX = 65535 +uint16 TEN_MILLI_SECONDS_IN_PAST = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg index a01230954..f45476300 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathHistory.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ PathPoint[] array uint8 MIN_SIZE = 0 uint8 MAX_SIZE = 40 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg index beb29a984..afe56fd92 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PathPoint.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # pathDeltaTime PathDeltaTime OPTIONAL # } # ------------------------------------------------------------------------------ + DeltaReferencePosition path_position PathDeltaTime path_delta_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg index 5e647048f..566e6c9ae 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PerformanceClass.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 7 uint8 UNAVAILABLE = 0 uint8 PERFORMANCE_CLASS_A = 1 uint8 PERFORMANCE_CLASS_B = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg index c905f4171..6efe47e5d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PhoneNumber.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ string value uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 16 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg index eb542bcf9..18fdd9a5c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosCentMass.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 63 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 63 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg index 69e6be2a2..0c72b9a6f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosConfidenceEllipse.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,6 +31,7 @@ # semiMajorOrientation HeadingValue # } # ------------------------------------------------------------------------------ + SemiAxisLength semi_major_confidence SemiAxisLength semi_minor_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg index dec614584..622ab1d0f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosFrontAx.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 20 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 20 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg index 56a23793c..5d6168e9f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosLonCarr.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 ONE_CENTIMETER = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg index f000268e6..050b310d7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PosPillar.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 30 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 30 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg index bab7e4e92..f11996d64 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfOccupants.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -72,3 +71,4 @@ uint8 BIT_INDEX_ROW_4_RIGHT_OCCUPIED = 16 uint8 BIT_INDEX_ROW_4_MID_OCCUPIED = 17 uint8 BIT_INDEX_ROW_4_NOT_DETECTABLE = 18 uint8 BIT_INDEX_ROW_4_NOT_PRESENT = 19 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg index 7db286c34..eea208f31 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositionOfPillars.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # ------------------------------------------------------------------------------ PosPillar[] array -int64 MIN_SIZE = 1 -int64 MAX_SIZE = 3 +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg index 1032ae4b1..e0292c4ea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PositioningSolutionType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,7 +32,7 @@ uint8 value uint8 NO_POSITIONING_SOLUTION = 0 uint8 S_GNSS = 1 uint8 D_GNSS = 2 -uint8 S_GNS_SPLUS_DR = 3 -uint8 D_GNS_SPLUS_DR = 4 +uint8 S_GNSS_PLUS_D_R = 3 +uint8 D_GNSS_PLUS_D_R = 4 uint8 D_R = 5 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg index 85a35798a..bee1a897e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PostCrashSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -37,3 +36,4 @@ uint8 ACCIDENT_WITHOUT_E_CALL_TRIGGERED = 1 uint8 ACCIDENT_WITH_E_CALL_MANUALLY_TRIGGERED = 2 uint8 ACCIDENT_WITH_E_CALL_AUTOMATICALLY_TRIGGERED = 3 uint8 ACCIDENT_WITH_E_CALL_TRIGGERED_WITHOUT_ACCESS_TO_CELLULAR_NETWORK = 4 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg index d1335c7cc..5a6ebbbd4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZone.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,6 +35,7 @@ # ... # } # ------------------------------------------------------------------------------ + ProtectedZoneType protected_zone_type TimestampIts expiry_time diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg index 2d5f9f9a4..cc6d8ea62 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedCommunicationZonesRSU.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ ProtectedCommunicationZone[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 16 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg index bb4f93c32..6a0344d74 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg index 97a3ead2e..7f1a3f2c2 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneRadius.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -29,7 +28,8 @@ # ProtectedZoneRadius ::= INTEGER {oneMeter(1)} (1..255,...) # ------------------------------------------------------------------------------ -int64 value -int64 MIN = 1 -int64 MAX = 255 -int64 ONE_METER = 1 +uint8 value +uint8 MIN = 1 +uint8 MAX = 255 +uint8 ONE_METER = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg index 9ba419cec..3283db4e0 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ProtectedZoneType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,5 @@ uint8 value uint8 PERMANENT_CEN_DSRC_TOLLING = 0 -# .extended uint8 TEMPORARY_CEN_DSRC_TOLLING = 1 diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg index 32c276aa5..f70514140 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivation.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # ptActivationData PtActivationData # } # ------------------------------------------------------------------------------ + PtActivationType pt_activation_type PtActivationData pt_activation_data diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg index 902dbf9e0..0fb3a6413 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationData.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ uint8[] value uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 20 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg index 1d3a14412..0d373552c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/PtActivationType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNDEFINED_CODING_TYPE = 0 uint8 R_09_16_CODING_TYPE = 1 uint8 VDV_50149_CODING_TYPE = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg index ea13c3cf8..bedf5e7f1 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferenceDenms.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # ------------------------------------------------------------------------------ ActionID[] array -int64 MIN_SIZE = 1 -int64 MAX_SIZE = 8 +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg index 738b78443..ff37f4ebf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ReferencePosition.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,6 +32,7 @@ # altitude Altitude # } # ------------------------------------------------------------------------------ + Latitude latitude Longitude longitude diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg index 4bdc9a00c..03f962736 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceDistance.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg index 23849c372..6a2060b60 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RelevanceTrafficDirection.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg index 7a88dc8db..e87b70032 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RequestResponseIndication.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg index 427e20f40..3cd20fa4f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RescueAndRecoveryWorkInProgressSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,3 +37,4 @@ uint8 RESCUE_HELICOPTER_LANDING = 2 uint8 POLICE_ACTIVITY_ONGOING = 3 uint8 MEDICAL_EMERGENCY_ONGOING = 4 uint8 CHILD_ABDUCTION_IN_PROGRESS = 5 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg index f9c80d5be..d5103c64e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RestrictedTypes.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -30,5 +29,6 @@ # ------------------------------------------------------------------------------ StationType[] array -int64 MIN_SIZE = 1 -int64 MAX_SIZE = 3 +uint8 MIN_SIZE = 1 +uint8 MAX_SIZE = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg index 7280b7c6b..e2615acec 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg index 5e18e5977..7948b4d6a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadWorksContainerExtended.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,6 +37,7 @@ # referenceDenms ReferenceDenms OPTIONAL # } # ------------------------------------------------------------------------------ + LightBarSirenInUse light_bar_siren_in_use bool light_bar_siren_in_use_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg index 017a34d21..153e11c4e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/RoadworksSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -39,3 +38,4 @@ uint8 SLOW_MOVING_ROAD_MAINTENANCE = 3 uint8 SHORT_TERM_STATIONARY_ROADWORKS = 4 uint8 STREET_CLEANING = 5 uint8 WINTER_SERVICE = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg index fbd569ec1..976c006d8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SemiAxisLength.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint16 MAX = 4095 uint16 ONE_CENTIMETER = 1 uint16 OUT_OF_RANGE = 4094 uint16 UNAVAILABLE = 4095 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg index 8fd8be07e..3ee9128cd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SequenceNumber.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg index 6286201a3..580af19c9 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SignalViolationSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 UNAVAILABLE = 0 uint8 STOP_SIGN_VIOLATION = 1 uint8 TRAFFIC_LIGHT_VIOLATION = 2 uint8 TURNING_REGULATION_VIOLATION = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg index 583baddcb..f0bc862ea 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SituationContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,6 +33,7 @@ # ... # } # ------------------------------------------------------------------------------ + InformationQuality information_quality CauseCode event_type diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg index ffc371dec..d7c7e96b7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SlowVehicleSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 CONVOY = 5 uint8 SNOWPLOUGH = 6 uint8 DEICING = 7 uint8 SALTING_VEHICLES = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg index 7bfb3f184..8f5fcd9d6 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpecialTransportType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 BIT_INDEX_HEAVY_LOAD = 0 uint8 BIT_INDEX_EXCESS_WIDTH = 1 uint8 BIT_INDEX_EXCESS_LENGTH = 2 uint8 BIT_INDEX_EXCESS_HEIGHT = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg index e6a686f59..ecfc591e4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Speed.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # speedConfidence SpeedConfidence # } # ------------------------------------------------------------------------------ + SpeedValue speed_value SpeedConfidence speed_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg index 3001fa3f3..487873b36 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ uint8 EQUAL_OR_WITHIN_ONE_CENTIMETER_PER_SEC = 1 uint8 EQUAL_OR_WITHIN_ONE_METER_PER_SEC = 100 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg index 5eb6c64c4..4cf1a9d03 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedLimit.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -33,3 +32,4 @@ uint8 value uint8 MIN = 1 uint8 MAX = 255 uint8 ONE_KM_PER_HOUR = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg index 978abe6e5..b3d89beff 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SpeedValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint16 MAX = 16383 uint16 STANDSTILL = 0 uint16 ONE_CENTIMETER_PER_SEC = 1 uint16 UNAVAILABLE = 16383 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg index 6cf2e47dc..9d36a5a65 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationID.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg index d84cf4192..104c6821e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -46,3 +45,4 @@ uint8 TRAILER = 9 uint8 SPECIAL_VEHICLES = 10 uint8 TRAM = 11 uint8 ROAD_SIDE_UNIT = 15 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg index 6cd027626..e0133c7a8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationarySince.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg index 11a49ee5b..07c536a89 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleContainer.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,6 +34,7 @@ # energyStorageType EnergyStorageType OPTIONAL # } # ------------------------------------------------------------------------------ + StationarySince stationary_since bool stationary_since_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg index a970bdcb5..190a7c78e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/StationaryVehicleSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -38,3 +37,4 @@ uint8 VEHICLE_BREAKDOWN = 2 uint8 POST_CRASH = 3 uint8 PUBLIC_TRANSPORT_STOP = 4 uint8 CARRYING_DANGEROUS_GOODS = 5 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg index eb08c754b..918cc7a8d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngle.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # steeringWheelAngleConfidence SteeringWheelAngleConfidence # } # ------------------------------------------------------------------------------ + SteeringWheelAngleValue steering_wheel_angle_value SteeringWheelAngleConfidence steering_wheel_angle_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg index 9c07b52b0..bf209a62e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 127 uint8 EQUAL_OR_WITHIN_ONE_POINT_FIVE_DEGREE = 1 uint8 OUT_OF_RANGE = 126 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg index aeae3ce54..fbda5ff63 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SteeringWheelAngleValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ int16 STRAIGHT = 0 int16 ONE_POINT_FIVE_DEGREES_TO_RIGHT = -1 int16 ONE_POINT_FIVE_DEGREES_TO_LEFT = 1 int16 UNAVAILABLE = 512 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg index ebc0b6600..5f328fa69 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/SubCauseCodeType.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg index 0a3e27072..2e351568e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Temperature.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int8 MAX = 67 int8 EQUAL_OR_SMALLER_THAN_MINUS_60_DEG = -60 int8 ONE_DEGREE_CELSIUS = 1 int8 EQUAL_OR_GREATER_THAN_67_DEG = 67 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg index ccdae355f..33ac2d5dd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Termination.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg index 8366db355..6871563ba 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TimestampIts.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint64 MIN = 0 uint64 MAX = 4398046511103 uint64 UTC_START_OF_2004 = 0 uint64 ONE_MILLISEC_AFTER_UTC_START_OF_2004 = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg index f3a2e2a48..db7a2bb0f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/Traces.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ PathHistory[] array uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 7 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg index 41b2503eb..38061b4a4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficConditionSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -41,3 +40,4 @@ uint8 TRAFFIC_STATIONARY = 5 uint8 TRAFFIC_JAM_SLIGHTLY_DECREASING = 6 uint8 TRAFFIC_JAM_DECREASING = 7 uint8 TRAFFIC_JAM_STRONGLY_DECREASING = 8 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg index c688d0470..cc8afc852 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TrafficRule.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg index e2f87591d..343d094dd 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TransmissionInterval.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint16 MIN = 1 uint16 MAX = 10000 uint16 ONE_MILLI_SECOND = 1 uint16 TEN_SECONDS = 10000 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg index 510f64696..99ccaa91d 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/TurningRadius.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 255 uint8 POINT_4_METERS = 1 uint8 UNAVAILABLE = 255 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg index 80ffff83c..e9beb0f3f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VDS.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,3 +30,4 @@ string value uint8 SIZE = 6 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg index 9e069e511..3cfc6ffe7 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/ValidityDuration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint32 MIN = 0 uint32 MAX = 86400 uint32 TIME_OF_DETECTION = 0 uint32 ONE_SECOND_AFTER_DETECTION = 1 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg index 814d2276a..40c794fa4 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleBreakdownSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -42,3 +41,4 @@ uint8 BRAKING_SYSTEM_PROBLEM = 6 uint8 STEERING_PROBLEM = 7 uint8 TYRE_PUNCTURE = 8 uint8 TYRE_PRESSURE_PROBLEM = 9 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg index e43ea5841..411ade20f 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleIdentification.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,9 +31,10 @@ # ... # } # ------------------------------------------------------------------------------ -WMInumber w_m_inumber -bool w_m_inumber_is_present -VDS v_ds -bool v_ds_is_present +WMInumber wm_inumber +bool wm_inumber_is_present + +VDS vds +bool vds_is_present diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg index 0b68fb8ef..0657adbdc 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLength.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # vehicleLengthConfidenceIndication VehicleLengthConfidenceIndication # } # ------------------------------------------------------------------------------ + VehicleLengthValue vehicle_length_value VehicleLengthConfidenceIndication vehicle_length_confidence_indication diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg index 5b5d5d4c7..b5a008bba 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthConfidenceIndication.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg index baed0b1ee..e253cfda3 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleLengthValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint16 MAX = 1023 uint16 TEN_CENTIMETERS = 1 uint16 OUT_OF_RANGE = 1022 uint16 UNAVAILABLE = 1023 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg index 986aab8fc..d74f09b5c 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleMass.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint16 MIN = 1 uint16 MAX = 1024 uint16 HUNDRED_KG = 1 uint16 UNAVAILABLE = 1024 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg index 3e089a89a..daeb43921 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleRole.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg index b0a8e7fa5..c209c3b57 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VehicleWidth.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 62 uint8 TEN_CENTIMETERS = 1 uint8 OUT_OF_RANGE = 61 uint8 UNAVAILABLE = 62 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg index 0ac4bda1a..3da431c59 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAcceleration.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # verticalAccelerationConfidence AccelerationConfidence # } # ------------------------------------------------------------------------------ + VerticalAccelerationValue vertical_acceleration_value AccelerationConfidence vertical_acceleration_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg index f0abb220c..4f208993e 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/VerticalAccelerationValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ int16 MAX = 161 int16 POINT_ONE_METER_PER_SEC_SQUARED_UP = 1 int16 POINT_ONE_METER_PER_SEC_SQUARED_DOWN = -1 int16 UNAVAILABLE = 161 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg index 22d1ceeab..34b682f9a 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WMInumber.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -32,3 +31,4 @@ string value uint8 MIN_SIZE = 1 uint8 MAX_SIZE = 3 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg index 0b7a691a5..af24dccaf 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WheelBaseVehicle.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -34,3 +33,4 @@ uint8 MIN = 1 uint8 MAX = 127 uint8 TEN_CENTIMETERS = 1 uint8 UNAVAILABLE = 127 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg index a4611cb8c..0f8080f05 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/WrongWayDrivingSubCauseCode.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -35,3 +34,4 @@ uint8 MAX = 255 uint8 UNAVAILABLE = 0 uint8 WRONG_LANE = 1 uint8 WRONG_DIRECTION = 2 + diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg index 7305b6027..2284e9ba8 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRate.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -31,6 +30,7 @@ # yawRateConfidence YawRateConfidence # } # ------------------------------------------------------------------------------ + YawRateValue yaw_rate_value YawRateConfidence yaw_rate_confidence diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg index a3a9eaab3..4150e4776 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateConfidence.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal diff --git a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg index 3cf3b6b18..9564c6bee 100644 --- a/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg +++ b/etsi_its_msgs/etsi_its_denm_msgs/msg/YawRateValue.msg @@ -2,7 +2,6 @@ # MIT License # # Copyright (c) 2023 Institute for Automotive Engineering (ika), RWTH Aachen University -# Copyright (c) 2024 Instituto de Telecomunicações, Universidade de Aveiro # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal @@ -36,3 +35,4 @@ int16 STRAIGHT = 0 int16 DEG_SEC_000_01_TO_RIGHT = -1 int16 DEG_SEC_000_01_TO_LEFT = 1 int16 UNAVAILABLE = 32767 +