From cc757879563d0adf015d18af451ec794c5213e87 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 11 May 2019 16:44:33 +0300 Subject: [PATCH 1/9] Removed CAN-specific statements from some type definitions --- uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan b/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan index 37cc3222..9b5f99b4 100644 --- a/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan +++ b/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan @@ -160,7 +160,7 @@ # Rule B. On expiration of the Request Timer (started as per rules A, B, or C): # 1. Request Timer restarts with a random interval of Trequest (chosen anew). # 2. The allocatee broadcasts an allocation request message, where the fields are populated as follows: -# node_id - the preferred node-ID, or 125 if the allocatee doesn't have any specific preference. +# node_id - the preferred node-ID, or the highest valid value if the allocatee doesn't have any preference. # unique_id - the 128-bit unique-ID of the allocatee, same value that is reported via uavcan.node.GetInfo. # # Rule C. On any allocation message, even if other rules also match: @@ -180,18 +180,18 @@ # If the message transfer is anonymous (i.e., allocation request), this is the preferred ID. # If the message transfer is non-anonymous (i.e., allocation response), this is the allocated ID. # -# If the allocatee does not have any preference, it should request the highest possible node-ID, which is 125, -# because 126 and 127 are reserved for network maintenance tools. Requesting 126 and 127 is not prohibited, +# If the allocatee does not have any preference, it should request the highest possible node-ID. Keep in mind that +# the two highest node ID values are reserved for network maintenance tools; requesting those is not prohibited, # but the allocator is recommended to avoid granting these node-ID, using nearest available lower value instead. # The allocator will traverse the allocation table starting from the preferred node-ID upward, # until a free node-ID is found (or the first ID reserved for network maintenance tools is reached). # If a free node-ID could not be found, the allocator will restart the search from the preferred node-ID # downward, until a free node-ID is found. In pseudocode: # -# uint8_t findFreeNodeID(const uint8_t preferred) // Returns >127 on failure (valid node-ID range from 0 to 127) +# uint16_t findFreeNodeID(const uint16_t preferred) // Returns 0xFFFF on failure # { # uint8_t candidate = preferred; -# while (candidate <= 125) +# while (candidate <= MAX_VALID_NODE_ID) // MAX_VALID_NODE_ID is transport-dependent # { # if (!isOccupied(candidate)) { return candidate; } # candidate++; @@ -202,7 +202,7 @@ # if (!isOccupied(candidate)) { return candidate; } # candidate--; # } -# return isOccupied(0) ? 255 : 0; +# return isOccupied(0) ? 0xFFFF : 0; # } uavcan.node.ID.1.0 node_id From 5cf665cce85e9a8a95c5d57320563d45e343fd54 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 11 May 2019 17:17:13 +0300 Subject: [PATCH 2/9] Typo --- uavcan/file/Error.1.0.uavcan | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uavcan/file/Error.1.0.uavcan b/uavcan/file/Error.1.0.uavcan index 3b75bfd0..dafbd187 100644 --- a/uavcan/file/Error.1.0.uavcan +++ b/uavcan/file/Error.1.0.uavcan @@ -9,8 +9,8 @@ uint16 UNKNOWN_ERROR = 65535 uint16 NOT_FOUND = 2 uint16 IO_ERROR = 5 uint16 ACCESS_DENIED = 13 -uint16 IS_DIRECTORY = 21 # I.e. attempted read/write on a path that points to a directory -uint16 INVALID_VALUE = 22 # E.g. file name is not valid for the target file system +uint16 IS_DIRECTORY = 21 # I.e., attempted read/write on a path that points to a directory +uint16 INVALID_VALUE = 22 # E.g., file name is not valid for the target file system uint16 FILE_TOO_LARGE = 27 uint16 OUT_OF_SPACE = 28 uint16 NOT_SUPPORTED = 38 From 815f7913722c22fa13d05707d1477a197bf76a71 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 11 May 2019 17:18:35 +0300 Subject: [PATCH 3/9] Enlarged the data buffer in udp.OutgoingPacket to 261 bytes to make a full use of the permitted maximum of 313 bytes --- .../internet/udp/32750.OutgoingPacket.0.1.uavcan | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/uavcan/internet/udp/32750.OutgoingPacket.0.1.uavcan b/uavcan/internet/udp/32750.OutgoingPacket.0.1.uavcan index 5b64b227..49995ec3 100644 --- a/uavcan/internet/udp/32750.OutgoingPacket.0.1.uavcan +++ b/uavcan/internet/udp/32750.OutgoingPacket.0.1.uavcan @@ -94,7 +94,7 @@ # Modem nodes are required to keep the NAT table entries alive for at least this amount of time, unless the # table is overflowed, in which case they are allowed to remove least recently used entries in favor of # newer ones. Modem nodes are required to be able to accommodate at least 100 entries in the NAT table. -uint32 NAT_ENTRY_MIN_TTL = 86400 # [second] +uint32 NAT_ENTRY_MIN_TTL = 24 * 60 * 60 # [second] # This field is set to an arbitrary value by the transmitting node in order to be able to match the response # with the locally kept context. The function of this field is virtually identical to that of UDP/IP port @@ -105,10 +105,6 @@ uint16 session_id # UDP destination port number. uint16 destination_port -# Option flags. -bool use_masquerading # Expect data back (i.e. instruct the modem to use the NAT table) -void7 - # Domain name or IP address where the payload should be forwarded to. # Note that broadcast addresses are allowed here, for example, 255.255.255.255. # Broadcasting with masquerading enabled works the same way as unicasting with masquerading enabled: the modem @@ -126,10 +122,17 @@ void7 void2 uint8[<=45] destination_address +@assert _offset_ % 8 == {0} + +# Option flags. +bool use_masquerading # Expect data back (i.e., instruct the modem to use the NAT table) +void6 + # Effective payload. This data will be forwarded to the remote host verbatim. # UDP packets that contain more than 508 bytes of payload may be dropped by some types of # communication equipment. Refer to RFC 791 and 2460 for an in-depth review. # UAVCAN further limits the maximum packet size to reduce the memory and traffic burden on the nodes. -uint8[<256] payload +uint8[<=261] payload @assert _offset_ % 8 == {0} +@assert _offset_.max / 8 == 313 From cd3ed3923b76b7368047c6aad3002fd5d1670f9e Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 11 May 2019 17:49:38 +0300 Subject: [PATCH 4/9] Automatic style enforcement in test.py --- .travis.yml | 2 +- test.py | 58 ++++++++++++++++++++++--------- uavcan/primitive/Empty.1.0.uavcan | 1 + 3 files changed, 43 insertions(+), 18 deletions(-) diff --git a/.travis.yml b/.travis.yml index a251ac74..d498d5cd 100644 --- a/.travis.yml +++ b/.travis.yml @@ -2,6 +2,6 @@ language: python python: - "3.6" before_install: - - pip install pydsdl + - pip install pydsdl>=0.7 script: - ./test.py diff --git a/test.py b/test.py index 83e84671..0b0247ac 100755 --- a/test.py +++ b/test.py @@ -4,16 +4,23 @@ import time import string import pydsdl +from functools import partial MAX_SERIALIZED_BIT_LENGTH = 313 * 8 # See README MAX_LINE_LENGTH = 120 +NAMESPACES_EXEMPTED_FROM_HEADER_COMMENT_REQUIREMENT = 'uavcan.primitive', 'uavcan.si' ALLOWED_CHARACTERS = set(string.digits + string.ascii_letters + string.punctuation + ' ') -def on_print(definition, line, value): - print('%s:%d: %s' % (definition.file_path, line, value), - file=sys.stderr) +def die_at(ty, line_index, *text): + prefix = '%s:%d:' % (ty.source_file_path, line_index + 1) + print(prefix, *text, file=sys.stderr) + sys.exit(1) + + +def on_print(file_path, line, value): + print('%s:%d: %s' % (file_path, line, value), file=sys.stderr) def compute_max_num_frames_canfd(bit_length): @@ -36,11 +43,11 @@ def compute_max_num_frames_canfd(bit_length): num_frames_to_str = lambda x: str(x) if x > 1 else ' ' # Return empty for single-frame transfers if isinstance(t, pydsdl.ServiceType): max_canfd_frames = ' '.join([ - num_frames_to_str(compute_max_num_frames_canfd(x.bit_length_range.max)) + num_frames_to_str(compute_max_num_frames_canfd(max(x.bit_length_set))) for x in (t.request_type, t.response_type) ]) else: - max_canfd_frames = num_frames_to_str(compute_max_num_frames_canfd(t.bit_length_range.max)) + max_canfd_frames = num_frames_to_str(compute_max_num_frames_canfd(max(t.bit_length_set))) print(str(t).ljust(58), str(t.fixed_port_id if t.has_fixed_port_id else '').rjust(5), @@ -51,23 +58,40 @@ def compute_max_num_frames_canfd(bit_length): largest = None for t in output: - for index, line in enumerate(open(t.source_file_path).readlines()): + text = open(t.source_file_path).read() + for index, line in enumerate(text.split('\n')): line = line.strip('\r\n') + abort = partial(die_at, t, index) + + # Check header comment + if index == 0 and line != '#': + if not any(map(lambda e: t.full_namespace.startswith(e), + NAMESPACES_EXEMPTED_FROM_HEADER_COMMENT_REQUIREMENT)): + abort('Every data type definition must have a header comment surrounded with "#\\n",', + 'unless it is a member of:', NAMESPACES_EXEMPTED_FROM_HEADER_COMMENT_REQUIREMENT) + + # Check trailing comment placement + # TODO: this test breaks on string literals containing "#" + if not line.startswith('#') and '#' in line and ' #' not in line: + abort('Trailing line comments must be separated from the preceding text with at least two spaces') + + if line != '#' and '#' in line and '# ' not in line: + abort('The text of a comment must be separated from the comment character with a single space') + + if line.endswith(' '): + abort('Trailing spaces are not permitted') # Check line length limit if len(line) > MAX_LINE_LENGTH: - print('%s:%d: Line is too long:' % (t.source_file_path, index + 1), - len(line), '>', MAX_LINE_LENGTH, 'chars', - file=sys.stderr) - sys.exit(1) + abort('Line is too long:', len(line), '>', MAX_LINE_LENGTH, 'chars') # Make sure we're not using any weird characters such as tabs or non-ASCII-printable for char_index, char in enumerate(line): if char not in ALLOWED_CHARACTERS: - print('%s:%d: Disallowed character' % (t.source_file_path, index + 1), - repr(char), 'code', ord(char), 'at column', char_index + 1, - file=sys.stderr) - sys.exit(1) + abort('Disallowed character', repr(char), 'code', ord(char), 'at column', char_index + 1) + + if not text.endswith('\n') or text.endswith('\n' * 2): + abort('A file must contain exactly one blank line at the end') if isinstance(t, pydsdl.ServiceType): tt = t.request_type, t.response_type @@ -75,12 +99,12 @@ def compute_max_num_frames_canfd(bit_length): tt = t, for t in tt: - largest = largest if largest and (largest.bit_length_range.max >= t.bit_length_range.max) else t + largest = largest if largest and (max(largest.bit_length_set) >= max(t.bit_length_set)) else t -if largest.bit_length_range.max > MAX_SERIALIZED_BIT_LENGTH: +if max(largest.bit_length_set) > MAX_SERIALIZED_BIT_LENGTH: print('The largest data type', largest, 'exceeds the bit length limit of', MAX_SERIALIZED_BIT_LENGTH, file=sys.stderr) sys.exit(1) else: - print('Largest data type is', largest, 'up to', (largest.bit_length_range.max + 7) // 8, 'bytes', + print('Largest data type is', largest, 'up to', (max(largest.bit_length_set) + 7) // 8, 'bytes', file=sys.stderr) diff --git a/uavcan/primitive/Empty.1.0.uavcan b/uavcan/primitive/Empty.1.0.uavcan index e69de29b..8b137891 100644 --- a/uavcan/primitive/Empty.1.0.uavcan +++ b/uavcan/primitive/Empty.1.0.uavcan @@ -0,0 +1 @@ + From 58da2f658745c15e674cdcba417f3de931b4e023 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 11 May 2019 17:58:59 +0300 Subject: [PATCH 5/9] The write buffer increased up to 192 bytes to maximize usage of the available 313 bytes per transfer --- uavcan/file/409.Write.1.0.uavcan | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uavcan/file/409.Write.1.0.uavcan b/uavcan/file/409.Write.1.0.uavcan index fa915826..1fbfe3f1 100644 --- a/uavcan/file/409.Write.1.0.uavcan +++ b/uavcan/file/409.Write.1.0.uavcan @@ -15,10 +15,10 @@ truncated uint40 offset Path.1.0 path -uint8[<=128] data +uint8[<=192] data # 192 = 128 + 64; the write protocol permits usage of smaller chunks. @assert _offset_ % 8 == {0} -@assert _offset_.max / 8 <= 300 +@assert _offset_.max / 8 <= 313 --- From f468909db282e524eb6410187f02a33720f196d4 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 14 May 2019 19:23:40 +0300 Subject: [PATCH 6/9] Elaboration on PnP table overflow --- uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan b/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan index 9b5f99b4..419660e7 100644 --- a/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan +++ b/uavcan/pnp/32741.NodeIDAllocationData.0.1.uavcan @@ -122,9 +122,11 @@ # The allocatee-allocator exchange logic differs between allocators and allocatees. For allocators, the logic is # trivial: upon reception of a request, the allocator performs an allocation and sends a response back. If the # allocation could not be performed for any reason (e.g., the allocation table is full, or there was a failure), -# no response is sent back (i.e., the request is simply ignored). The allocator that could not complete an allocation -# for any reason is recommended to emit a diagnostic message with a human-readable description of the problem. -# For allocatees, the logic is described below. +# no response is sent back (i.e., the request is simply ignored); the recommended strategy for the allocatee is to +# continue sending new allocation requests until a response is granted or a higher-level system (e.g., a maintenance +# technician or some automation) intervenes to rectify the problem (e.g., by purging the allocation table). +# The allocator that could not complete an allocation for any reason is recommended to emit a diagnostic message +# with a human-readable description of the problem. For allocatees, the logic is described below. # # This message is used for PnP node-ID allocation on all transports where the maximum transmission unit size is # sufficiently large. For low-MTU transports such as CAN 2.0 there is a dedicated message definition that takes into From 26ab2c94a631a1d191852be553ee56b1f34938b0 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 21 Jul 2019 18:10:36 +0300 Subject: [PATCH 7/9] Stabilization of node.GetInfo and node.ExecuteCommand --- uavcan/node/{430.GetInfo.0.1.uavcan => 430.GetInfo.1.0.uavcan} | 0 ...35.ExecuteCommand.0.1.uavcan => 435.ExecuteCommand.1.0.uavcan} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename uavcan/node/{430.GetInfo.0.1.uavcan => 430.GetInfo.1.0.uavcan} (100%) rename uavcan/node/{435.ExecuteCommand.0.1.uavcan => 435.ExecuteCommand.1.0.uavcan} (100%) diff --git a/uavcan/node/430.GetInfo.0.1.uavcan b/uavcan/node/430.GetInfo.1.0.uavcan similarity index 100% rename from uavcan/node/430.GetInfo.0.1.uavcan rename to uavcan/node/430.GetInfo.1.0.uavcan diff --git a/uavcan/node/435.ExecuteCommand.0.1.uavcan b/uavcan/node/435.ExecuteCommand.1.0.uavcan similarity index 100% rename from uavcan/node/435.ExecuteCommand.0.1.uavcan rename to uavcan/node/435.ExecuteCommand.1.0.uavcan From a532bfa7d09409f1d160bdf5240ebd7430a662ba Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 21 Jul 2019 18:16:59 +0300 Subject: [PATCH 8/9] Stabilization of register.* --- .../{384.Access.0.1.uavcan => 384.Access.1.0.uavcan} | 6 +++--- .../register/{385.List.0.1.uavcan => 385.List.1.0.uavcan} | 2 +- uavcan/register/{Name.0.1.uavcan => Name.1.0.uavcan} | 0 uavcan/register/{Value.0.1.uavcan => Value.1.0.uavcan} | 0 4 files changed, 4 insertions(+), 4 deletions(-) rename uavcan/register/{384.Access.0.1.uavcan => 384.Access.1.0.uavcan} (99%) rename uavcan/register/{385.List.0.1.uavcan => 385.List.1.0.uavcan} (95%) rename uavcan/register/{Name.0.1.uavcan => Name.1.0.uavcan} (100%) rename uavcan/register/{Value.0.1.uavcan => Value.1.0.uavcan} (100%) diff --git a/uavcan/register/384.Access.0.1.uavcan b/uavcan/register/384.Access.1.0.uavcan similarity index 99% rename from uavcan/register/384.Access.0.1.uavcan rename to uavcan/register/384.Access.1.0.uavcan index aee93075..67cbe787 100644 --- a/uavcan/register/384.Access.0.1.uavcan +++ b/uavcan/register/384.Access.1.0.uavcan @@ -75,13 +75,13 @@ # The name of the accessed register. Must not be empty. # Use the List service to obtain the list of registers on the node. -Name.0.1 name +Name.1.0 name @assert _offset_ % 8 == {0} # Value to be written. Empty if no write is required. void4 -Value.0.1 value +Value.1.0 value @assert _offset_.min % 8 == 0 @assert _offset_.max % 8 == 0 @@ -120,7 +120,7 @@ void2 # Empty value means that the register does not exist (in this case the flags should be cleared/ignored). # By comparing the returned value against the write request the caller can determine whether the register # was written successfully, unless write was not requested. -Value.0.1 value +Value.1.0 value @assert _offset_.min % 8 == 0 @assert _offset_.max % 8 == 0 diff --git a/uavcan/register/385.List.0.1.uavcan b/uavcan/register/385.List.1.0.uavcan similarity index 95% rename from uavcan/register/385.List.0.1.uavcan rename to uavcan/register/385.List.1.0.uavcan index ef4e08a6..fab443a7 100644 --- a/uavcan/register/385.List.0.1.uavcan +++ b/uavcan/register/385.List.1.0.uavcan @@ -8,6 +8,6 @@ uint16 index --- # Empty name in response means that the index is out of bounds, i.e., discovery is finished. -Name.0.1 name +Name.1.0 name @assert _offset_ % 8 == {0} diff --git a/uavcan/register/Name.0.1.uavcan b/uavcan/register/Name.1.0.uavcan similarity index 100% rename from uavcan/register/Name.0.1.uavcan rename to uavcan/register/Name.1.0.uavcan diff --git a/uavcan/register/Value.0.1.uavcan b/uavcan/register/Value.1.0.uavcan similarity index 100% rename from uavcan/register/Value.0.1.uavcan rename to uavcan/register/Value.1.0.uavcan From acb48c15288510bffea3797d76e3eca21d6413dc Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 30 Aug 2019 12:41:00 +0300 Subject: [PATCH 9/9] Remove ambiguous timestamp, refactor SI namespace; closes #63 --- uavcan/si/acceleration/Scalar.1.0.uavcan | 3 --- uavcan/si/acceleration/Vector3.1.0.uavcan | 4 ---- uavcan/si/angle/Quaternion.1.0.uavcan | 4 ---- uavcan/si/angle/Scalar.1.0.uavcan | 3 --- uavcan/si/angular_velocity/Scalar.1.0.uavcan | 3 --- uavcan/si/angular_velocity/Vector3.1.0.uavcan | 4 ---- uavcan/si/duration/Scalar.1.0.uavcan | 3 --- uavcan/si/duration/WideScalar.1.0.uavcan | 3 --- uavcan/si/electric_charge/Scalar.1.0.uavcan | 3 --- uavcan/si/electric_current/Scalar.1.0.uavcan | 3 --- uavcan/si/energy/Scalar.1.0.uavcan | 3 --- uavcan/si/length/Scalar.1.0.uavcan | 3 --- uavcan/si/length/Vector3.1.0.uavcan | 4 ---- uavcan/si/length/WideVector3.1.0.uavcan | 4 ---- .../magnetic_field_strength/Scalar.1.0.uavcan | 3 --- .../Vector3.1.0.uavcan | 4 ---- uavcan/si/mass/Scalar.1.0.uavcan | 3 --- uavcan/si/power/Scalar.1.0.uavcan | 3 --- uavcan/si/pressure/Scalar.1.0.uavcan | 3 --- .../si/sample/acceleration/Scalar.1.0.uavcan | 2 ++ .../si/sample/acceleration/Vector3.1.0.uavcan | 3 +++ uavcan/si/sample/angle/Quaternion.1.0.uavcan | 3 +++ uavcan/si/sample/angle/Scalar.1.0.uavcan | 2 ++ .../sample/angular_velocity/Scalar.1.0.uavcan | 2 ++ .../angular_velocity/Vector3.1.0.uavcan | 3 +++ uavcan/si/sample/duration/Scalar.1.0.uavcan | 2 ++ .../si/sample/duration/WideScalar.1.0.uavcan | 2 ++ .../sample/electric_charge/Scalar.1.0.uavcan | 2 ++ .../sample/electric_current/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/energy/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/length/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/length/Vector3.1.0.uavcan | 3 +++ .../si/sample/length/WideVector3.1.0.uavcan | 3 +++ .../magnetic_field_strength/Scalar.1.0.uavcan | 2 ++ .../Vector3.1.0.uavcan | 3 +++ uavcan/si/sample/mass/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/power/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/pressure/Scalar.1.0.uavcan | 2 ++ .../si/sample/temperature/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/velocity/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/velocity/Vector3.1.0.uavcan | 3 +++ uavcan/si/sample/voltage/Scalar.1.0.uavcan | 2 ++ uavcan/si/sample/volume/Scalar.1.0.uavcan | 2 ++ .../volumetric_flow_rate/Scalar.1.0.uavcan | 2 ++ uavcan/si/temperature/Scalar.1.0.uavcan | 3 --- uavcan/si/unit/acceleration/Scalar.1.0.uavcan | 1 + .../si/unit/acceleration/Vector3.1.0.uavcan | 1 + uavcan/si/unit/angle/Quaternion.1.0.uavcan | 1 + uavcan/si/unit/angle/Scalar.1.0.uavcan | 1 + .../unit/angular_velocity/Scalar.1.0.uavcan | 1 + .../unit/angular_velocity/Vector3.1.0.uavcan | 1 + uavcan/si/unit/duration/Scalar.1.0.uavcan | 1 + uavcan/si/unit/duration/WideScalar.1.0.uavcan | 1 + .../si/unit/electric_charge/Scalar.1.0.uavcan | 1 + .../unit/electric_current/Scalar.1.0.uavcan | 1 + uavcan/si/unit/energy/Scalar.1.0.uavcan | 1 + uavcan/si/unit/length/Scalar.1.0.uavcan | 1 + uavcan/si/unit/length/Vector3.1.0.uavcan | 1 + uavcan/si/unit/length/WideVector3.1.0.uavcan | 1 + .../magnetic_field_strength/Scalar.1.0.uavcan | 1 + .../Vector3.1.0.uavcan | 1 + uavcan/si/unit/mass/Scalar.1.0.uavcan | 1 + uavcan/si/unit/power/Scalar.1.0.uavcan | 1 + uavcan/si/unit/pressure/Scalar.1.0.uavcan | 1 + uavcan/si/unit/temperature/Scalar.1.0.uavcan | 1 + uavcan/si/unit/velocity/Scalar.1.0.uavcan | 1 + uavcan/si/unit/velocity/Vector3.1.0.uavcan | 1 + uavcan/si/unit/voltage/Scalar.1.0.uavcan | 1 + uavcan/si/unit/volume/Scalar.1.0.uavcan | 1 + .../volumetric_flow_rate/Scalar.1.0.uavcan | 1 + uavcan/si/velocity/Scalar.1.0.uavcan | 3 --- uavcan/si/velocity/Vector3.1.0.uavcan | 4 ---- uavcan/si/voltage/Scalar.1.0.uavcan | 3 --- uavcan/si/volume/Scalar.1.0.uavcan | 3 --- .../si/volumetric_flow_rate/Scalar.1.0.uavcan | 3 --- .../SynchronizedAmbiguousTimestamp.1.0.uavcan | 19 ------------------- 76 files changed, 82 insertions(+), 101 deletions(-) delete mode 100644 uavcan/si/acceleration/Scalar.1.0.uavcan delete mode 100644 uavcan/si/acceleration/Vector3.1.0.uavcan delete mode 100644 uavcan/si/angle/Quaternion.1.0.uavcan delete mode 100644 uavcan/si/angle/Scalar.1.0.uavcan delete mode 100644 uavcan/si/angular_velocity/Scalar.1.0.uavcan delete mode 100644 uavcan/si/angular_velocity/Vector3.1.0.uavcan delete mode 100644 uavcan/si/duration/Scalar.1.0.uavcan delete mode 100644 uavcan/si/duration/WideScalar.1.0.uavcan delete mode 100644 uavcan/si/electric_charge/Scalar.1.0.uavcan delete mode 100644 uavcan/si/electric_current/Scalar.1.0.uavcan delete mode 100644 uavcan/si/energy/Scalar.1.0.uavcan delete mode 100644 uavcan/si/length/Scalar.1.0.uavcan delete mode 100644 uavcan/si/length/Vector3.1.0.uavcan delete mode 100644 uavcan/si/length/WideVector3.1.0.uavcan delete mode 100644 uavcan/si/magnetic_field_strength/Scalar.1.0.uavcan delete mode 100644 uavcan/si/magnetic_field_strength/Vector3.1.0.uavcan delete mode 100644 uavcan/si/mass/Scalar.1.0.uavcan delete mode 100644 uavcan/si/power/Scalar.1.0.uavcan delete mode 100644 uavcan/si/pressure/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/acceleration/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/acceleration/Vector3.1.0.uavcan create mode 100644 uavcan/si/sample/angle/Quaternion.1.0.uavcan create mode 100644 uavcan/si/sample/angle/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/angular_velocity/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/angular_velocity/Vector3.1.0.uavcan create mode 100644 uavcan/si/sample/duration/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/duration/WideScalar.1.0.uavcan create mode 100644 uavcan/si/sample/electric_charge/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/electric_current/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/energy/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/length/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/length/Vector3.1.0.uavcan create mode 100644 uavcan/si/sample/length/WideVector3.1.0.uavcan create mode 100644 uavcan/si/sample/magnetic_field_strength/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/magnetic_field_strength/Vector3.1.0.uavcan create mode 100644 uavcan/si/sample/mass/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/power/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/pressure/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/temperature/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/velocity/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/velocity/Vector3.1.0.uavcan create mode 100644 uavcan/si/sample/voltage/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/volume/Scalar.1.0.uavcan create mode 100644 uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.uavcan delete mode 100644 uavcan/si/temperature/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/acceleration/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/acceleration/Vector3.1.0.uavcan create mode 100644 uavcan/si/unit/angle/Quaternion.1.0.uavcan create mode 100644 uavcan/si/unit/angle/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/angular_velocity/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/angular_velocity/Vector3.1.0.uavcan create mode 100644 uavcan/si/unit/duration/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/duration/WideScalar.1.0.uavcan create mode 100644 uavcan/si/unit/electric_charge/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/electric_current/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/energy/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/length/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/length/Vector3.1.0.uavcan create mode 100644 uavcan/si/unit/length/WideVector3.1.0.uavcan create mode 100644 uavcan/si/unit/magnetic_field_strength/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/magnetic_field_strength/Vector3.1.0.uavcan create mode 100644 uavcan/si/unit/mass/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/power/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/pressure/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/temperature/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/velocity/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/velocity/Vector3.1.0.uavcan create mode 100644 uavcan/si/unit/voltage/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/volume/Scalar.1.0.uavcan create mode 100644 uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.uavcan delete mode 100644 uavcan/si/velocity/Scalar.1.0.uavcan delete mode 100644 uavcan/si/velocity/Vector3.1.0.uavcan delete mode 100644 uavcan/si/voltage/Scalar.1.0.uavcan delete mode 100644 uavcan/si/volume/Scalar.1.0.uavcan delete mode 100644 uavcan/si/volumetric_flow_rate/Scalar.1.0.uavcan delete mode 100644 uavcan/time/SynchronizedAmbiguousTimestamp.1.0.uavcan diff --git a/uavcan/si/acceleration/Scalar.1.0.uavcan b/uavcan/si/acceleration/Scalar.1.0.uavcan deleted file mode 100644 index e3a487cb..00000000 --- a/uavcan/si/acceleration/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 meter_per_second_per_second -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/acceleration/Vector3.1.0.uavcan b/uavcan/si/acceleration/Vector3.1.0.uavcan deleted file mode 100644 index 1e351acd..00000000 --- a/uavcan/si/acceleration/Vector3.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32[3] meter_per_second_per_second -@assert _offset_ / 8 == {15} -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/angle/Quaternion.1.0.uavcan b/uavcan/si/angle/Quaternion.1.0.uavcan deleted file mode 100644 index 4c8ee81e..00000000 --- a/uavcan/si/angle/Quaternion.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32[4] wxyz -@assert _offset_ / 8 == {19} # Optimized for three CAN 2.0 frames -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/angle/Scalar.1.0.uavcan b/uavcan/si/angle/Scalar.1.0.uavcan deleted file mode 100644 index 2b3d969f..00000000 --- a/uavcan/si/angle/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 radian -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/angular_velocity/Scalar.1.0.uavcan b/uavcan/si/angular_velocity/Scalar.1.0.uavcan deleted file mode 100644 index 079cd09c..00000000 --- a/uavcan/si/angular_velocity/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 radian_per_second -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/angular_velocity/Vector3.1.0.uavcan b/uavcan/si/angular_velocity/Vector3.1.0.uavcan deleted file mode 100644 index d0582b13..00000000 --- a/uavcan/si/angular_velocity/Vector3.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32[3] radian_per_second -@assert _offset_ / 8 == {15} -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/duration/Scalar.1.0.uavcan b/uavcan/si/duration/Scalar.1.0.uavcan deleted file mode 100644 index 31bfac90..00000000 --- a/uavcan/si/duration/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 second -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/duration/WideScalar.1.0.uavcan b/uavcan/si/duration/WideScalar.1.0.uavcan deleted file mode 100644 index fc5de52c..00000000 --- a/uavcan/si/duration/WideScalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float64 second -@assert _offset_ / 8 == {11} # Two CAN 2.0 frames diff --git a/uavcan/si/electric_charge/Scalar.1.0.uavcan b/uavcan/si/electric_charge/Scalar.1.0.uavcan deleted file mode 100644 index c6040209..00000000 --- a/uavcan/si/electric_charge/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 coulomb -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/electric_current/Scalar.1.0.uavcan b/uavcan/si/electric_current/Scalar.1.0.uavcan deleted file mode 100644 index 1946b472..00000000 --- a/uavcan/si/electric_current/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 ampere -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/energy/Scalar.1.0.uavcan b/uavcan/si/energy/Scalar.1.0.uavcan deleted file mode 100644 index 52692c77..00000000 --- a/uavcan/si/energy/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 joule -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/length/Scalar.1.0.uavcan b/uavcan/si/length/Scalar.1.0.uavcan deleted file mode 100644 index 18c1c195..00000000 --- a/uavcan/si/length/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 meter -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/length/Vector3.1.0.uavcan b/uavcan/si/length/Vector3.1.0.uavcan deleted file mode 100644 index aa10861d..00000000 --- a/uavcan/si/length/Vector3.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32[3] meter -@assert _offset_ / 8 == {15} -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/length/WideVector3.1.0.uavcan b/uavcan/si/length/WideVector3.1.0.uavcan deleted file mode 100644 index 6234a4a4..00000000 --- a/uavcan/si/length/WideVector3.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float64[3] meter -@assert _offset_ / 8 == {27} -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/magnetic_field_strength/Scalar.1.0.uavcan b/uavcan/si/magnetic_field_strength/Scalar.1.0.uavcan deleted file mode 100644 index 811ded25..00000000 --- a/uavcan/si/magnetic_field_strength/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 tesla -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/magnetic_field_strength/Vector3.1.0.uavcan b/uavcan/si/magnetic_field_strength/Vector3.1.0.uavcan deleted file mode 100644 index 7595c53b..00000000 --- a/uavcan/si/magnetic_field_strength/Vector3.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32[3] tesla -@assert _offset_ / 8 == {15} -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/mass/Scalar.1.0.uavcan b/uavcan/si/mass/Scalar.1.0.uavcan deleted file mode 100644 index ab9c302b..00000000 --- a/uavcan/si/mass/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 kilogram -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/power/Scalar.1.0.uavcan b/uavcan/si/power/Scalar.1.0.uavcan deleted file mode 100644 index 45ff6e5c..00000000 --- a/uavcan/si/power/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 watt -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/pressure/Scalar.1.0.uavcan b/uavcan/si/pressure/Scalar.1.0.uavcan deleted file mode 100644 index ec8c1b71..00000000 --- a/uavcan/si/pressure/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 pascal -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/sample/acceleration/Scalar.1.0.uavcan b/uavcan/si/sample/acceleration/Scalar.1.0.uavcan new file mode 100644 index 00000000..e33298d2 --- /dev/null +++ b/uavcan/si/sample/acceleration/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 meter_per_second_per_second diff --git a/uavcan/si/sample/acceleration/Vector3.1.0.uavcan b/uavcan/si/sample/acceleration/Vector3.1.0.uavcan new file mode 100644 index 00000000..daec1ab1 --- /dev/null +++ b/uavcan/si/sample/acceleration/Vector3.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32[3] meter_per_second_per_second +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/angle/Quaternion.1.0.uavcan b/uavcan/si/sample/angle/Quaternion.1.0.uavcan new file mode 100644 index 00000000..fc1d921c --- /dev/null +++ b/uavcan/si/sample/angle/Quaternion.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32[4] wxyz +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/angle/Scalar.1.0.uavcan b/uavcan/si/sample/angle/Scalar.1.0.uavcan new file mode 100644 index 00000000..17f6bcb6 --- /dev/null +++ b/uavcan/si/sample/angle/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 radian diff --git a/uavcan/si/sample/angular_velocity/Scalar.1.0.uavcan b/uavcan/si/sample/angular_velocity/Scalar.1.0.uavcan new file mode 100644 index 00000000..21e7a3ad --- /dev/null +++ b/uavcan/si/sample/angular_velocity/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 radian_per_second diff --git a/uavcan/si/sample/angular_velocity/Vector3.1.0.uavcan b/uavcan/si/sample/angular_velocity/Vector3.1.0.uavcan new file mode 100644 index 00000000..2ab27810 --- /dev/null +++ b/uavcan/si/sample/angular_velocity/Vector3.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32[3] radian_per_second +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/duration/Scalar.1.0.uavcan b/uavcan/si/sample/duration/Scalar.1.0.uavcan new file mode 100644 index 00000000..6b8c23bf --- /dev/null +++ b/uavcan/si/sample/duration/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 second diff --git a/uavcan/si/sample/duration/WideScalar.1.0.uavcan b/uavcan/si/sample/duration/WideScalar.1.0.uavcan new file mode 100644 index 00000000..d6b2b7ba --- /dev/null +++ b/uavcan/si/sample/duration/WideScalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float64 second diff --git a/uavcan/si/sample/electric_charge/Scalar.1.0.uavcan b/uavcan/si/sample/electric_charge/Scalar.1.0.uavcan new file mode 100644 index 00000000..8101662b --- /dev/null +++ b/uavcan/si/sample/electric_charge/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 coulomb diff --git a/uavcan/si/sample/electric_current/Scalar.1.0.uavcan b/uavcan/si/sample/electric_current/Scalar.1.0.uavcan new file mode 100644 index 00000000..ccf6a4ed --- /dev/null +++ b/uavcan/si/sample/electric_current/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 ampere diff --git a/uavcan/si/sample/energy/Scalar.1.0.uavcan b/uavcan/si/sample/energy/Scalar.1.0.uavcan new file mode 100644 index 00000000..7c192f16 --- /dev/null +++ b/uavcan/si/sample/energy/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 joule diff --git a/uavcan/si/sample/length/Scalar.1.0.uavcan b/uavcan/si/sample/length/Scalar.1.0.uavcan new file mode 100644 index 00000000..73757d26 --- /dev/null +++ b/uavcan/si/sample/length/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 meter diff --git a/uavcan/si/sample/length/Vector3.1.0.uavcan b/uavcan/si/sample/length/Vector3.1.0.uavcan new file mode 100644 index 00000000..64bc706a --- /dev/null +++ b/uavcan/si/sample/length/Vector3.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32[3] meter +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/length/WideVector3.1.0.uavcan b/uavcan/si/sample/length/WideVector3.1.0.uavcan new file mode 100644 index 00000000..c5d17ef2 --- /dev/null +++ b/uavcan/si/sample/length/WideVector3.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float64[3] meter +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.uavcan b/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.uavcan new file mode 100644 index 00000000..c5c43775 --- /dev/null +++ b/uavcan/si/sample/magnetic_field_strength/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 tesla diff --git a/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.uavcan b/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.uavcan new file mode 100644 index 00000000..99a0181d --- /dev/null +++ b/uavcan/si/sample/magnetic_field_strength/Vector3.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32[3] tesla +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/mass/Scalar.1.0.uavcan b/uavcan/si/sample/mass/Scalar.1.0.uavcan new file mode 100644 index 00000000..eb862de0 --- /dev/null +++ b/uavcan/si/sample/mass/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 kilogram diff --git a/uavcan/si/sample/power/Scalar.1.0.uavcan b/uavcan/si/sample/power/Scalar.1.0.uavcan new file mode 100644 index 00000000..647046d0 --- /dev/null +++ b/uavcan/si/sample/power/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 watt diff --git a/uavcan/si/sample/pressure/Scalar.1.0.uavcan b/uavcan/si/sample/pressure/Scalar.1.0.uavcan new file mode 100644 index 00000000..a58f2f9d --- /dev/null +++ b/uavcan/si/sample/pressure/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 pascal diff --git a/uavcan/si/sample/temperature/Scalar.1.0.uavcan b/uavcan/si/sample/temperature/Scalar.1.0.uavcan new file mode 100644 index 00000000..17dd9f2c --- /dev/null +++ b/uavcan/si/sample/temperature/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 kelvin diff --git a/uavcan/si/sample/velocity/Scalar.1.0.uavcan b/uavcan/si/sample/velocity/Scalar.1.0.uavcan new file mode 100644 index 00000000..f68f69b7 --- /dev/null +++ b/uavcan/si/sample/velocity/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 meter_per_second diff --git a/uavcan/si/sample/velocity/Vector3.1.0.uavcan b/uavcan/si/sample/velocity/Vector3.1.0.uavcan new file mode 100644 index 00000000..c01d7504 --- /dev/null +++ b/uavcan/si/sample/velocity/Vector3.1.0.uavcan @@ -0,0 +1,3 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32[3] meter_per_second +@assert _offset_ % 8 == {0} diff --git a/uavcan/si/sample/voltage/Scalar.1.0.uavcan b/uavcan/si/sample/voltage/Scalar.1.0.uavcan new file mode 100644 index 00000000..03463079 --- /dev/null +++ b/uavcan/si/sample/voltage/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 volt diff --git a/uavcan/si/sample/volume/Scalar.1.0.uavcan b/uavcan/si/sample/volume/Scalar.1.0.uavcan new file mode 100644 index 00000000..3539642a --- /dev/null +++ b/uavcan/si/sample/volume/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 cubic_meter diff --git a/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.uavcan b/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.uavcan new file mode 100644 index 00000000..07b6ed39 --- /dev/null +++ b/uavcan/si/sample/volumetric_flow_rate/Scalar.1.0.uavcan @@ -0,0 +1,2 @@ +uavcan.time.SynchronizedTimestamp.1.0 timestamp +float32 cubic_meter_per_second diff --git a/uavcan/si/temperature/Scalar.1.0.uavcan b/uavcan/si/temperature/Scalar.1.0.uavcan deleted file mode 100644 index 837f698f..00000000 --- a/uavcan/si/temperature/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 kelvin -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/unit/acceleration/Scalar.1.0.uavcan b/uavcan/si/unit/acceleration/Scalar.1.0.uavcan new file mode 100644 index 00000000..6df592ce --- /dev/null +++ b/uavcan/si/unit/acceleration/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 meter_per_second_per_second diff --git a/uavcan/si/unit/acceleration/Vector3.1.0.uavcan b/uavcan/si/unit/acceleration/Vector3.1.0.uavcan new file mode 100644 index 00000000..3301c2ce --- /dev/null +++ b/uavcan/si/unit/acceleration/Vector3.1.0.uavcan @@ -0,0 +1 @@ +float32[3] meter_per_second_per_second diff --git a/uavcan/si/unit/angle/Quaternion.1.0.uavcan b/uavcan/si/unit/angle/Quaternion.1.0.uavcan new file mode 100644 index 00000000..f64e94da --- /dev/null +++ b/uavcan/si/unit/angle/Quaternion.1.0.uavcan @@ -0,0 +1 @@ +float32[4] wxyz diff --git a/uavcan/si/unit/angle/Scalar.1.0.uavcan b/uavcan/si/unit/angle/Scalar.1.0.uavcan new file mode 100644 index 00000000..e86cc30f --- /dev/null +++ b/uavcan/si/unit/angle/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 radian diff --git a/uavcan/si/unit/angular_velocity/Scalar.1.0.uavcan b/uavcan/si/unit/angular_velocity/Scalar.1.0.uavcan new file mode 100644 index 00000000..b64f5e56 --- /dev/null +++ b/uavcan/si/unit/angular_velocity/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 radian_per_second diff --git a/uavcan/si/unit/angular_velocity/Vector3.1.0.uavcan b/uavcan/si/unit/angular_velocity/Vector3.1.0.uavcan new file mode 100644 index 00000000..c6e91400 --- /dev/null +++ b/uavcan/si/unit/angular_velocity/Vector3.1.0.uavcan @@ -0,0 +1 @@ +float32[3] radian_per_second diff --git a/uavcan/si/unit/duration/Scalar.1.0.uavcan b/uavcan/si/unit/duration/Scalar.1.0.uavcan new file mode 100644 index 00000000..d96dcee9 --- /dev/null +++ b/uavcan/si/unit/duration/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 second diff --git a/uavcan/si/unit/duration/WideScalar.1.0.uavcan b/uavcan/si/unit/duration/WideScalar.1.0.uavcan new file mode 100644 index 00000000..84015dd3 --- /dev/null +++ b/uavcan/si/unit/duration/WideScalar.1.0.uavcan @@ -0,0 +1 @@ +float64 second diff --git a/uavcan/si/unit/electric_charge/Scalar.1.0.uavcan b/uavcan/si/unit/electric_charge/Scalar.1.0.uavcan new file mode 100644 index 00000000..2299f5a3 --- /dev/null +++ b/uavcan/si/unit/electric_charge/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 coulomb diff --git a/uavcan/si/unit/electric_current/Scalar.1.0.uavcan b/uavcan/si/unit/electric_current/Scalar.1.0.uavcan new file mode 100644 index 00000000..6a7974da --- /dev/null +++ b/uavcan/si/unit/electric_current/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 ampere diff --git a/uavcan/si/unit/energy/Scalar.1.0.uavcan b/uavcan/si/unit/energy/Scalar.1.0.uavcan new file mode 100644 index 00000000..2e4f8714 --- /dev/null +++ b/uavcan/si/unit/energy/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 joule diff --git a/uavcan/si/unit/length/Scalar.1.0.uavcan b/uavcan/si/unit/length/Scalar.1.0.uavcan new file mode 100644 index 00000000..357b9061 --- /dev/null +++ b/uavcan/si/unit/length/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 meter diff --git a/uavcan/si/unit/length/Vector3.1.0.uavcan b/uavcan/si/unit/length/Vector3.1.0.uavcan new file mode 100644 index 00000000..b5b43ca6 --- /dev/null +++ b/uavcan/si/unit/length/Vector3.1.0.uavcan @@ -0,0 +1 @@ +float32[3] meter diff --git a/uavcan/si/unit/length/WideVector3.1.0.uavcan b/uavcan/si/unit/length/WideVector3.1.0.uavcan new file mode 100644 index 00000000..47dcca87 --- /dev/null +++ b/uavcan/si/unit/length/WideVector3.1.0.uavcan @@ -0,0 +1 @@ +float64[3] meter diff --git a/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.uavcan b/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.uavcan new file mode 100644 index 00000000..07397e3a --- /dev/null +++ b/uavcan/si/unit/magnetic_field_strength/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 tesla diff --git a/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.uavcan b/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.uavcan new file mode 100644 index 00000000..2c22cebb --- /dev/null +++ b/uavcan/si/unit/magnetic_field_strength/Vector3.1.0.uavcan @@ -0,0 +1 @@ +float32[3] tesla diff --git a/uavcan/si/unit/mass/Scalar.1.0.uavcan b/uavcan/si/unit/mass/Scalar.1.0.uavcan new file mode 100644 index 00000000..db476a17 --- /dev/null +++ b/uavcan/si/unit/mass/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 kilogram diff --git a/uavcan/si/unit/power/Scalar.1.0.uavcan b/uavcan/si/unit/power/Scalar.1.0.uavcan new file mode 100644 index 00000000..8bcf4538 --- /dev/null +++ b/uavcan/si/unit/power/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 watt diff --git a/uavcan/si/unit/pressure/Scalar.1.0.uavcan b/uavcan/si/unit/pressure/Scalar.1.0.uavcan new file mode 100644 index 00000000..a3cc4a24 --- /dev/null +++ b/uavcan/si/unit/pressure/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 pascal diff --git a/uavcan/si/unit/temperature/Scalar.1.0.uavcan b/uavcan/si/unit/temperature/Scalar.1.0.uavcan new file mode 100644 index 00000000..b4e868d7 --- /dev/null +++ b/uavcan/si/unit/temperature/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 kelvin diff --git a/uavcan/si/unit/velocity/Scalar.1.0.uavcan b/uavcan/si/unit/velocity/Scalar.1.0.uavcan new file mode 100644 index 00000000..4288d465 --- /dev/null +++ b/uavcan/si/unit/velocity/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 meter_per_second diff --git a/uavcan/si/unit/velocity/Vector3.1.0.uavcan b/uavcan/si/unit/velocity/Vector3.1.0.uavcan new file mode 100644 index 00000000..3cdfe491 --- /dev/null +++ b/uavcan/si/unit/velocity/Vector3.1.0.uavcan @@ -0,0 +1 @@ +float32[3] meter_per_second diff --git a/uavcan/si/unit/voltage/Scalar.1.0.uavcan b/uavcan/si/unit/voltage/Scalar.1.0.uavcan new file mode 100644 index 00000000..a05a33aa --- /dev/null +++ b/uavcan/si/unit/voltage/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 volt diff --git a/uavcan/si/unit/volume/Scalar.1.0.uavcan b/uavcan/si/unit/volume/Scalar.1.0.uavcan new file mode 100644 index 00000000..e76efaac --- /dev/null +++ b/uavcan/si/unit/volume/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 cubic_meter diff --git a/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.uavcan b/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.uavcan new file mode 100644 index 00000000..c0f3cdb3 --- /dev/null +++ b/uavcan/si/unit/volumetric_flow_rate/Scalar.1.0.uavcan @@ -0,0 +1 @@ +float32 cubic_meter_per_second diff --git a/uavcan/si/velocity/Scalar.1.0.uavcan b/uavcan/si/velocity/Scalar.1.0.uavcan deleted file mode 100644 index cb78337e..00000000 --- a/uavcan/si/velocity/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 meter_per_second -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/velocity/Vector3.1.0.uavcan b/uavcan/si/velocity/Vector3.1.0.uavcan deleted file mode 100644 index 626ef439..00000000 --- a/uavcan/si/velocity/Vector3.1.0.uavcan +++ /dev/null @@ -1,4 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32[3] meter_per_second -@assert _offset_ / 8 == {15} -@assert _offset_ % 8 == {0} diff --git a/uavcan/si/voltage/Scalar.1.0.uavcan b/uavcan/si/voltage/Scalar.1.0.uavcan deleted file mode 100644 index 1fa958c7..00000000 --- a/uavcan/si/voltage/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 volt -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/volume/Scalar.1.0.uavcan b/uavcan/si/volume/Scalar.1.0.uavcan deleted file mode 100644 index d9d52f3e..00000000 --- a/uavcan/si/volume/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 cubic_meter -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/si/volumetric_flow_rate/Scalar.1.0.uavcan b/uavcan/si/volumetric_flow_rate/Scalar.1.0.uavcan deleted file mode 100644 index 97d84ebc..00000000 --- a/uavcan/si/volumetric_flow_rate/Scalar.1.0.uavcan +++ /dev/null @@ -1,3 +0,0 @@ -uavcan.time.SynchronizedAmbiguousTimestamp.1.0 timestamp -float32 cubic_meter_per_second -@assert _offset_ / 8 == {7} # Single CAN 2.0 frame diff --git a/uavcan/time/SynchronizedAmbiguousTimestamp.1.0.uavcan b/uavcan/time/SynchronizedAmbiguousTimestamp.1.0.uavcan deleted file mode 100644 index 1609fe8e..00000000 --- a/uavcan/time/SynchronizedAmbiguousTimestamp.1.0.uavcan +++ /dev/null @@ -1,19 +0,0 @@ -# -# Nested data type used for representing a network-wide synchronized timestamp with 10 (ten) microsecond resolution. -# Unlike the wider alternative, this timestamp value expires in ~167 seconds due to integer overflow of the -# microsecond timestamp field: 2**24 / 1e5 = 167.77216 seconds. -# This data type should not be used unless network throughput and latency are of utmost importance, -# because it is inherently unsafe: a delay of more than the specified above limit will invalidate the timestamp -# and its users will not be able to detect that. Instead, the full non-overflowing non-ambiguous timestamp -# should be preferred. -# - -# Zero means that the time is not known. -uint24 UNKNOWN = 0 - -# Expiration timeout. -uint28 OVERFLOW_PERIOD_us = 167772160 # [microsecond] - -# Overflowing sub-timestamp, 10 microseconds per least significant bit. -# Overflows every ~167 seconds. -truncated uint24 decamicrosecond # [second*10^-5]